1#![doc = "MAVLink uAvionix dialect."]
2#![doc = ""]
3#![doc = "This file was automatically generated, do not edit."]
4#[cfg(feature = "arbitrary")]
5use arbitrary::Arbitrary;
6#[allow(unused_imports)]
7use bitflags::bitflags;
8use mavlink_core::{bytes::Bytes, bytes_mut::BytesMut, MavlinkVersion, Message, MessageData};
9#[allow(unused_imports)]
10use num_derive::FromPrimitive;
11#[allow(unused_imports)]
12use num_derive::ToPrimitive;
13#[allow(unused_imports)]
14use num_traits::FromPrimitive;
15#[allow(unused_imports)]
16use num_traits::ToPrimitive;
17#[cfg(feature = "serde")]
18use serde::{Deserialize, Serialize};
19#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
20#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21#[cfg_attr(feature = "serde", serde(tag = "type"))]
22#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23#[repr(u32)]
24#[doc = "Actuator configuration, used to change a setting on an actuator. Component information metadata can be used to know which outputs support which commands."]
25pub enum ActuatorConfiguration {
26 #[doc = "Do nothing."]
27 ACTUATOR_CONFIGURATION_NONE = 0,
28 #[doc = "Command the actuator to beep now."]
29 ACTUATOR_CONFIGURATION_BEEP = 1,
30 #[doc = "Permanently set the actuator (ESC) to 3D mode (reversible thrust)."]
31 ACTUATOR_CONFIGURATION_3D_MODE_ON = 2,
32 #[doc = "Permanently set the actuator (ESC) to non 3D mode (non-reversible thrust)."]
33 ACTUATOR_CONFIGURATION_3D_MODE_OFF = 3,
34 #[doc = "Permanently set the actuator (ESC) to spin direction 1 (which can be clockwise or counter-clockwise)."]
35 ACTUATOR_CONFIGURATION_SPIN_DIRECTION1 = 4,
36 #[doc = "Permanently set the actuator (ESC) to spin direction 2 (opposite of direction 1)."]
37 ACTUATOR_CONFIGURATION_SPIN_DIRECTION2 = 5,
38}
39impl ActuatorConfiguration {
40 pub const DEFAULT: Self = Self::ACTUATOR_CONFIGURATION_NONE;
41}
42impl Default for ActuatorConfiguration {
43 fn default() -> Self {
44 Self::DEFAULT
45 }
46}
47#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
48#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
49#[cfg_attr(feature = "serde", serde(tag = "type"))]
50#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
51#[repr(u32)]
52#[doc = "Actuator output function. Values greater or equal to 1000 are autopilot-specific."]
53pub enum ActuatorOutputFunction {
54 #[doc = "No function (disabled)."]
55 ACTUATOR_OUTPUT_FUNCTION_NONE = 0,
56 #[doc = "Motor 1"]
57 ACTUATOR_OUTPUT_FUNCTION_MOTOR1 = 1,
58 #[doc = "Motor 2"]
59 ACTUATOR_OUTPUT_FUNCTION_MOTOR2 = 2,
60 #[doc = "Motor 3"]
61 ACTUATOR_OUTPUT_FUNCTION_MOTOR3 = 3,
62 #[doc = "Motor 4"]
63 ACTUATOR_OUTPUT_FUNCTION_MOTOR4 = 4,
64 #[doc = "Motor 5"]
65 ACTUATOR_OUTPUT_FUNCTION_MOTOR5 = 5,
66 #[doc = "Motor 6"]
67 ACTUATOR_OUTPUT_FUNCTION_MOTOR6 = 6,
68 #[doc = "Motor 7"]
69 ACTUATOR_OUTPUT_FUNCTION_MOTOR7 = 7,
70 #[doc = "Motor 8"]
71 ACTUATOR_OUTPUT_FUNCTION_MOTOR8 = 8,
72 #[doc = "Motor 9"]
73 ACTUATOR_OUTPUT_FUNCTION_MOTOR9 = 9,
74 #[doc = "Motor 10"]
75 ACTUATOR_OUTPUT_FUNCTION_MOTOR10 = 10,
76 #[doc = "Motor 11"]
77 ACTUATOR_OUTPUT_FUNCTION_MOTOR11 = 11,
78 #[doc = "Motor 12"]
79 ACTUATOR_OUTPUT_FUNCTION_MOTOR12 = 12,
80 #[doc = "Motor 13"]
81 ACTUATOR_OUTPUT_FUNCTION_MOTOR13 = 13,
82 #[doc = "Motor 14"]
83 ACTUATOR_OUTPUT_FUNCTION_MOTOR14 = 14,
84 #[doc = "Motor 15"]
85 ACTUATOR_OUTPUT_FUNCTION_MOTOR15 = 15,
86 #[doc = "Motor 16"]
87 ACTUATOR_OUTPUT_FUNCTION_MOTOR16 = 16,
88 #[doc = "Servo 1"]
89 ACTUATOR_OUTPUT_FUNCTION_SERVO1 = 33,
90 #[doc = "Servo 2"]
91 ACTUATOR_OUTPUT_FUNCTION_SERVO2 = 34,
92 #[doc = "Servo 3"]
93 ACTUATOR_OUTPUT_FUNCTION_SERVO3 = 35,
94 #[doc = "Servo 4"]
95 ACTUATOR_OUTPUT_FUNCTION_SERVO4 = 36,
96 #[doc = "Servo 5"]
97 ACTUATOR_OUTPUT_FUNCTION_SERVO5 = 37,
98 #[doc = "Servo 6"]
99 ACTUATOR_OUTPUT_FUNCTION_SERVO6 = 38,
100 #[doc = "Servo 7"]
101 ACTUATOR_OUTPUT_FUNCTION_SERVO7 = 39,
102 #[doc = "Servo 8"]
103 ACTUATOR_OUTPUT_FUNCTION_SERVO8 = 40,
104 #[doc = "Servo 9"]
105 ACTUATOR_OUTPUT_FUNCTION_SERVO9 = 41,
106 #[doc = "Servo 10"]
107 ACTUATOR_OUTPUT_FUNCTION_SERVO10 = 42,
108 #[doc = "Servo 11"]
109 ACTUATOR_OUTPUT_FUNCTION_SERVO11 = 43,
110 #[doc = "Servo 12"]
111 ACTUATOR_OUTPUT_FUNCTION_SERVO12 = 44,
112 #[doc = "Servo 13"]
113 ACTUATOR_OUTPUT_FUNCTION_SERVO13 = 45,
114 #[doc = "Servo 14"]
115 ACTUATOR_OUTPUT_FUNCTION_SERVO14 = 46,
116 #[doc = "Servo 15"]
117 ACTUATOR_OUTPUT_FUNCTION_SERVO15 = 47,
118 #[doc = "Servo 16"]
119 ACTUATOR_OUTPUT_FUNCTION_SERVO16 = 48,
120}
121impl ActuatorOutputFunction {
122 pub const DEFAULT: Self = Self::ACTUATOR_OUTPUT_FUNCTION_NONE;
123}
124impl Default for ActuatorOutputFunction {
125 fn default() -> Self {
126 Self::DEFAULT
127 }
128}
129#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
130#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
131#[cfg_attr(feature = "serde", serde(tag = "type"))]
132#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
133#[repr(u32)]
134#[doc = "Enumeration of the ADSB altimeter types"]
135pub enum AdsbAltitudeType {
136 #[doc = "Altitude reported from a Baro source using QNH reference"]
137 ADSB_ALTITUDE_TYPE_PRESSURE_QNH = 0,
138 #[doc = "Altitude reported from a GNSS source"]
139 ADSB_ALTITUDE_TYPE_GEOMETRIC = 1,
140}
141impl AdsbAltitudeType {
142 pub const DEFAULT: Self = Self::ADSB_ALTITUDE_TYPE_PRESSURE_QNH;
143}
144impl Default for AdsbAltitudeType {
145 fn default() -> Self {
146 Self::DEFAULT
147 }
148}
149#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
150#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
151#[cfg_attr(feature = "serde", serde(tag = "type"))]
152#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
153#[repr(u32)]
154#[doc = "ADSB classification for the type of vehicle emitting the transponder signal"]
155pub enum AdsbEmitterType {
156 ADSB_EMITTER_TYPE_NO_INFO = 0,
157 ADSB_EMITTER_TYPE_LIGHT = 1,
158 ADSB_EMITTER_TYPE_SMALL = 2,
159 ADSB_EMITTER_TYPE_LARGE = 3,
160 ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE = 4,
161 ADSB_EMITTER_TYPE_HEAVY = 5,
162 ADSB_EMITTER_TYPE_HIGHLY_MANUV = 6,
163 ADSB_EMITTER_TYPE_ROTOCRAFT = 7,
164 ADSB_EMITTER_TYPE_UNASSIGNED = 8,
165 ADSB_EMITTER_TYPE_GLIDER = 9,
166 ADSB_EMITTER_TYPE_LIGHTER_AIR = 10,
167 ADSB_EMITTER_TYPE_PARACHUTE = 11,
168 ADSB_EMITTER_TYPE_ULTRA_LIGHT = 12,
169 ADSB_EMITTER_TYPE_UNASSIGNED2 = 13,
170 ADSB_EMITTER_TYPE_UAV = 14,
171 ADSB_EMITTER_TYPE_SPACE = 15,
172 ADSB_EMITTER_TYPE_UNASSGINED3 = 16,
173 ADSB_EMITTER_TYPE_EMERGENCY_SURFACE = 17,
174 ADSB_EMITTER_TYPE_SERVICE_SURFACE = 18,
175 ADSB_EMITTER_TYPE_POINT_OBSTACLE = 19,
176}
177impl AdsbEmitterType {
178 pub const DEFAULT: Self = Self::ADSB_EMITTER_TYPE_NO_INFO;
179}
180impl Default for AdsbEmitterType {
181 fn default() -> Self {
182 Self::DEFAULT
183 }
184}
185bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These flags indicate status such as data validity of each data source. Set = data valid"] pub struct AdsbFlags : u16 { const ADSB_FLAGS_VALID_COORDS = 1 ; const ADSB_FLAGS_VALID_ALTITUDE = 2 ; const ADSB_FLAGS_VALID_HEADING = 4 ; const ADSB_FLAGS_VALID_VELOCITY = 8 ; const ADSB_FLAGS_VALID_CALLSIGN = 16 ; const ADSB_FLAGS_VALID_SQUAWK = 32 ; const ADSB_FLAGS_SIMULATED = 64 ; const ADSB_FLAGS_VERTICAL_VELOCITY_VALID = 128 ; const ADSB_FLAGS_BARO_VALID = 256 ; const ADSB_FLAGS_SOURCE_UAT = 32768 ; } }
186impl AdsbFlags {
187 pub const DEFAULT: Self = Self::ADSB_FLAGS_VALID_COORDS;
188}
189impl Default for AdsbFlags {
190 fn default() -> Self {
191 Self::DEFAULT
192 }
193}
194bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These flags are used in the AIS_VESSEL.fields bitmask to indicate validity of data in the other message fields. When set, the data is valid."] pub struct AisFlags : u16 { # [doc = "1 = Position accuracy less than 10m, 0 = position accuracy greater than 10m."] const AIS_FLAGS_POSITION_ACCURACY = 1 ; const AIS_FLAGS_VALID_COG = 2 ; const AIS_FLAGS_VALID_VELOCITY = 4 ; # [doc = "1 = Velocity over 52.5765m/s (102.2 knots)"] const AIS_FLAGS_HIGH_VELOCITY = 8 ; const AIS_FLAGS_VALID_TURN_RATE = 16 ; # [doc = "Only the sign of the returned turn rate value is valid, either greater than 5deg/30s or less than -5deg/30s"] const AIS_FLAGS_TURN_RATE_SIGN_ONLY = 32 ; const AIS_FLAGS_VALID_DIMENSIONS = 64 ; # [doc = "Distance to bow is larger than 511m"] const AIS_FLAGS_LARGE_BOW_DIMENSION = 128 ; # [doc = "Distance to stern is larger than 511m"] const AIS_FLAGS_LARGE_STERN_DIMENSION = 256 ; # [doc = "Distance to port side is larger than 63m"] const AIS_FLAGS_LARGE_PORT_DIMENSION = 512 ; # [doc = "Distance to starboard side is larger than 63m"] const AIS_FLAGS_LARGE_STARBOARD_DIMENSION = 1024 ; const AIS_FLAGS_VALID_CALLSIGN = 2048 ; const AIS_FLAGS_VALID_NAME = 4096 ; } }
195impl AisFlags {
196 pub const DEFAULT: Self = Self::AIS_FLAGS_POSITION_ACCURACY;
197}
198impl Default for AisFlags {
199 fn default() -> Self {
200 Self::DEFAULT
201 }
202}
203#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
204#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
205#[cfg_attr(feature = "serde", serde(tag = "type"))]
206#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
207#[repr(u32)]
208#[doc = "Navigational status of AIS vessel, enum duplicated from AIS standard, <https://gpsd.gitlab.io/gpsd/AIVDM.html>"]
209pub enum AisNavStatus {
210 #[doc = "Under way using engine."]
211 UNDER_WAY = 0,
212 AIS_NAV_ANCHORED = 1,
213 AIS_NAV_UN_COMMANDED = 2,
214 AIS_NAV_RESTRICTED_MANOEUVERABILITY = 3,
215 AIS_NAV_DRAUGHT_CONSTRAINED = 4,
216 AIS_NAV_MOORED = 5,
217 AIS_NAV_AGROUND = 6,
218 AIS_NAV_FISHING = 7,
219 AIS_NAV_SAILING = 8,
220 AIS_NAV_RESERVED_HSC = 9,
221 AIS_NAV_RESERVED_WIG = 10,
222 AIS_NAV_RESERVED_1 = 11,
223 AIS_NAV_RESERVED_2 = 12,
224 AIS_NAV_RESERVED_3 = 13,
225 #[doc = "Search And Rescue Transponder."]
226 AIS_NAV_AIS_SART = 14,
227 #[doc = "Not available (default)."]
228 AIS_NAV_UNKNOWN = 15,
229}
230impl AisNavStatus {
231 pub const DEFAULT: Self = Self::UNDER_WAY;
232}
233impl Default for AisNavStatus {
234 fn default() -> Self {
235 Self::DEFAULT
236 }
237}
238#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
239#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
240#[cfg_attr(feature = "serde", serde(tag = "type"))]
241#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
242#[repr(u32)]
243#[doc = "Type of AIS vessel, enum duplicated from AIS standard, <https://gpsd.gitlab.io/gpsd/AIVDM.html>"]
244pub enum AisType {
245 #[doc = "Not available (default)."]
246 AIS_TYPE_UNKNOWN = 0,
247 AIS_TYPE_RESERVED_1 = 1,
248 AIS_TYPE_RESERVED_2 = 2,
249 AIS_TYPE_RESERVED_3 = 3,
250 AIS_TYPE_RESERVED_4 = 4,
251 AIS_TYPE_RESERVED_5 = 5,
252 AIS_TYPE_RESERVED_6 = 6,
253 AIS_TYPE_RESERVED_7 = 7,
254 AIS_TYPE_RESERVED_8 = 8,
255 AIS_TYPE_RESERVED_9 = 9,
256 AIS_TYPE_RESERVED_10 = 10,
257 AIS_TYPE_RESERVED_11 = 11,
258 AIS_TYPE_RESERVED_12 = 12,
259 AIS_TYPE_RESERVED_13 = 13,
260 AIS_TYPE_RESERVED_14 = 14,
261 AIS_TYPE_RESERVED_15 = 15,
262 AIS_TYPE_RESERVED_16 = 16,
263 AIS_TYPE_RESERVED_17 = 17,
264 AIS_TYPE_RESERVED_18 = 18,
265 AIS_TYPE_RESERVED_19 = 19,
266 #[doc = "Wing In Ground effect."]
267 AIS_TYPE_WIG = 20,
268 AIS_TYPE_WIG_HAZARDOUS_A = 21,
269 AIS_TYPE_WIG_HAZARDOUS_B = 22,
270 AIS_TYPE_WIG_HAZARDOUS_C = 23,
271 AIS_TYPE_WIG_HAZARDOUS_D = 24,
272 AIS_TYPE_WIG_RESERVED_1 = 25,
273 AIS_TYPE_WIG_RESERVED_2 = 26,
274 AIS_TYPE_WIG_RESERVED_3 = 27,
275 AIS_TYPE_WIG_RESERVED_4 = 28,
276 AIS_TYPE_WIG_RESERVED_5 = 29,
277 AIS_TYPE_FISHING = 30,
278 AIS_TYPE_TOWING = 31,
279 #[doc = "Towing: length exceeds 200m or breadth exceeds 25m."]
280 AIS_TYPE_TOWING_LARGE = 32,
281 #[doc = "Dredging or other underwater ops."]
282 AIS_TYPE_DREDGING = 33,
283 AIS_TYPE_DIVING = 34,
284 AIS_TYPE_MILITARY = 35,
285 AIS_TYPE_SAILING = 36,
286 AIS_TYPE_PLEASURE = 37,
287 AIS_TYPE_RESERVED_20 = 38,
288 AIS_TYPE_RESERVED_21 = 39,
289 #[doc = "High Speed Craft."]
290 AIS_TYPE_HSC = 40,
291 AIS_TYPE_HSC_HAZARDOUS_A = 41,
292 AIS_TYPE_HSC_HAZARDOUS_B = 42,
293 AIS_TYPE_HSC_HAZARDOUS_C = 43,
294 AIS_TYPE_HSC_HAZARDOUS_D = 44,
295 AIS_TYPE_HSC_RESERVED_1 = 45,
296 AIS_TYPE_HSC_RESERVED_2 = 46,
297 AIS_TYPE_HSC_RESERVED_3 = 47,
298 AIS_TYPE_HSC_RESERVED_4 = 48,
299 AIS_TYPE_HSC_UNKNOWN = 49,
300 AIS_TYPE_PILOT = 50,
301 #[doc = "Search And Rescue vessel."]
302 AIS_TYPE_SAR = 51,
303 AIS_TYPE_TUG = 52,
304 AIS_TYPE_PORT_TENDER = 53,
305 #[doc = "Anti-pollution equipment."]
306 AIS_TYPE_ANTI_POLLUTION = 54,
307 AIS_TYPE_LAW_ENFORCEMENT = 55,
308 AIS_TYPE_SPARE_LOCAL_1 = 56,
309 AIS_TYPE_SPARE_LOCAL_2 = 57,
310 AIS_TYPE_MEDICAL_TRANSPORT = 58,
311 #[doc = "Noncombatant ship according to RR Resolution No. 18."]
312 AIS_TYPE_NONECOMBATANT = 59,
313 AIS_TYPE_PASSENGER = 60,
314 AIS_TYPE_PASSENGER_HAZARDOUS_A = 61,
315 AIS_TYPE_PASSENGER_HAZARDOUS_B = 62,
316 AIS_TYPE_PASSENGER_HAZARDOUS_C = 63,
317 AIS_TYPE_PASSENGER_HAZARDOUS_D = 64,
318 AIS_TYPE_PASSENGER_RESERVED_1 = 65,
319 AIS_TYPE_PASSENGER_RESERVED_2 = 66,
320 AIS_TYPE_PASSENGER_RESERVED_3 = 67,
321 AIS_TYPE_PASSENGER_RESERVED_4 = 68,
322 AIS_TYPE_PASSENGER_UNKNOWN = 69,
323 AIS_TYPE_CARGO = 70,
324 AIS_TYPE_CARGO_HAZARDOUS_A = 71,
325 AIS_TYPE_CARGO_HAZARDOUS_B = 72,
326 AIS_TYPE_CARGO_HAZARDOUS_C = 73,
327 AIS_TYPE_CARGO_HAZARDOUS_D = 74,
328 AIS_TYPE_CARGO_RESERVED_1 = 75,
329 AIS_TYPE_CARGO_RESERVED_2 = 76,
330 AIS_TYPE_CARGO_RESERVED_3 = 77,
331 AIS_TYPE_CARGO_RESERVED_4 = 78,
332 AIS_TYPE_CARGO_UNKNOWN = 79,
333 AIS_TYPE_TANKER = 80,
334 AIS_TYPE_TANKER_HAZARDOUS_A = 81,
335 AIS_TYPE_TANKER_HAZARDOUS_B = 82,
336 AIS_TYPE_TANKER_HAZARDOUS_C = 83,
337 AIS_TYPE_TANKER_HAZARDOUS_D = 84,
338 AIS_TYPE_TANKER_RESERVED_1 = 85,
339 AIS_TYPE_TANKER_RESERVED_2 = 86,
340 AIS_TYPE_TANKER_RESERVED_3 = 87,
341 AIS_TYPE_TANKER_RESERVED_4 = 88,
342 AIS_TYPE_TANKER_UNKNOWN = 89,
343 AIS_TYPE_OTHER = 90,
344 AIS_TYPE_OTHER_HAZARDOUS_A = 91,
345 AIS_TYPE_OTHER_HAZARDOUS_B = 92,
346 AIS_TYPE_OTHER_HAZARDOUS_C = 93,
347 AIS_TYPE_OTHER_HAZARDOUS_D = 94,
348 AIS_TYPE_OTHER_RESERVED_1 = 95,
349 AIS_TYPE_OTHER_RESERVED_2 = 96,
350 AIS_TYPE_OTHER_RESERVED_3 = 97,
351 AIS_TYPE_OTHER_RESERVED_4 = 98,
352 AIS_TYPE_OTHER_UNKNOWN = 99,
353}
354impl AisType {
355 pub const DEFAULT: Self = Self::AIS_TYPE_UNKNOWN;
356}
357impl Default for AisType {
358 fn default() -> Self {
359 Self::DEFAULT
360 }
361}
362bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates that none of the setpoint dimensions should be ignored."] pub struct AttitudeTargetTypemask : u8 { # [doc = "Ignore body roll rate"] const ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE = 1 ; # [doc = "Ignore body pitch rate"] const ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE = 2 ; # [doc = "Ignore body yaw rate"] const ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE = 4 ; # [doc = "Use 3D body thrust setpoint instead of throttle"] const ATTITUDE_TARGET_TYPEMASK_THRUST_BODY_SET = 32 ; # [doc = "Ignore throttle"] const ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE = 64 ; # [doc = "Ignore attitude"] const ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE = 128 ; } }
363impl AttitudeTargetTypemask {
364 pub const DEFAULT: Self = Self::ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE;
365}
366impl Default for AttitudeTargetTypemask {
367 fn default() -> Self {
368 Self::DEFAULT
369 }
370}
371#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
372#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
373#[cfg_attr(feature = "serde", serde(tag = "type"))]
374#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
375#[repr(u32)]
376#[doc = "Axes that will be autotuned by MAV_CMD_DO_AUTOTUNE_ENABLE. Note that at least one flag must be set in MAV_CMD_DO_AUTOTUNE_ENABLE.param2: if none are set, the flight stack will tune its default set of axes."]
377pub enum AutotuneAxis {
378 #[doc = "Autotune roll axis."]
379 AUTOTUNE_AXIS_ROLL = 1,
380 #[doc = "Autotune pitch axis."]
381 AUTOTUNE_AXIS_PITCH = 2,
382 #[doc = "Autotune yaw axis."]
383 AUTOTUNE_AXIS_YAW = 4,
384}
385impl AutotuneAxis {
386 pub const DEFAULT: Self = Self::AUTOTUNE_AXIS_ROLL;
387}
388impl Default for AutotuneAxis {
389 fn default() -> Self {
390 Self::DEFAULT
391 }
392}
393bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Camera capability flags (Bitmap)"] pub struct CameraCapFlags : u32 { # [doc = "Camera is able to record video"] const CAMERA_CAP_FLAGS_CAPTURE_VIDEO = 1 ; # [doc = "Camera is able to capture images"] const CAMERA_CAP_FLAGS_CAPTURE_IMAGE = 2 ; # [doc = "Camera has separate Video and Image/Photo modes (MAV_CMD_SET_CAMERA_MODE)"] const CAMERA_CAP_FLAGS_HAS_MODES = 4 ; # [doc = "Camera can capture images while in video mode"] const CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE = 8 ; # [doc = "Camera can capture videos while in Photo/Image mode"] const CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE = 16 ; # [doc = "Camera has image survey mode (MAV_CMD_SET_CAMERA_MODE)"] const CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE = 32 ; # [doc = "Camera has basic zoom control (MAV_CMD_SET_CAMERA_ZOOM)"] const CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM = 64 ; # [doc = "Camera has basic focus control (MAV_CMD_SET_CAMERA_FOCUS)"] const CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS = 128 ; # [doc = "Camera has video streaming capabilities (request VIDEO_STREAM_INFORMATION with MAV_CMD_REQUEST_MESSAGE for video streaming info)"] const CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM = 256 ; # [doc = "Camera supports tracking of a point on the camera view."] const CAMERA_CAP_FLAGS_HAS_TRACKING_POINT = 512 ; # [doc = "Camera supports tracking of a selection rectangle on the camera view."] const CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE = 1024 ; # [doc = "Camera supports tracking geo status (CAMERA_TRACKING_GEO_STATUS)."] const CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS = 2048 ; # [doc = "Camera supports absolute thermal range (request CAMERA_THERMAL_RANGE with MAV_CMD_REQUEST_MESSAGE)."] const CAMERA_CAP_FLAGS_HAS_THERMAL_RANGE = 4096 ; } }
394impl CameraCapFlags {
395 pub const DEFAULT: Self = Self::CAMERA_CAP_FLAGS_CAPTURE_VIDEO;
396}
397impl Default for CameraCapFlags {
398 fn default() -> Self {
399 Self::DEFAULT
400 }
401}
402#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
403#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
404#[cfg_attr(feature = "serde", serde(tag = "type"))]
405#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
406#[repr(u32)]
407#[doc = "Camera Modes."]
408pub enum CameraMode {
409 #[doc = "Camera is in image/photo capture mode."]
410 CAMERA_MODE_IMAGE = 0,
411 #[doc = "Camera is in video capture mode."]
412 CAMERA_MODE_VIDEO = 1,
413 #[doc = "Camera is in image survey capture mode. It allows for camera controller to do specific settings for surveys."]
414 CAMERA_MODE_IMAGE_SURVEY = 2,
415}
416impl CameraMode {
417 pub const DEFAULT: Self = Self::CAMERA_MODE_IMAGE;
418}
419impl Default for CameraMode {
420 fn default() -> Self {
421 Self::DEFAULT
422 }
423}
424#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
425#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
426#[cfg_attr(feature = "serde", serde(tag = "type"))]
427#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
428#[repr(u32)]
429#[doc = "Camera sources for MAV_CMD_SET_CAMERA_SOURCE"]
430pub enum CameraSource {
431 #[doc = "Default camera source."]
432 CAMERA_SOURCE_DEFAULT = 0,
433 #[doc = "RGB camera source."]
434 CAMERA_SOURCE_RGB = 1,
435 #[doc = "IR camera source."]
436 CAMERA_SOURCE_IR = 2,
437 #[doc = "NDVI camera source."]
438 CAMERA_SOURCE_NDVI = 3,
439}
440impl CameraSource {
441 pub const DEFAULT: Self = Self::CAMERA_SOURCE_DEFAULT;
442}
443impl Default for CameraSource {
444 fn default() -> Self {
445 Self::DEFAULT
446 }
447}
448#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
449#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
450#[cfg_attr(feature = "serde", serde(tag = "type"))]
451#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
452#[repr(u32)]
453#[doc = "Camera tracking modes"]
454pub enum CameraTrackingMode {
455 #[doc = "Not tracking"]
456 CAMERA_TRACKING_MODE_NONE = 0,
457 #[doc = "Target is a point"]
458 CAMERA_TRACKING_MODE_POINT = 1,
459 #[doc = "Target is a rectangle"]
460 CAMERA_TRACKING_MODE_RECTANGLE = 2,
461}
462impl CameraTrackingMode {
463 pub const DEFAULT: Self = Self::CAMERA_TRACKING_MODE_NONE;
464}
465impl Default for CameraTrackingMode {
466 fn default() -> Self {
467 Self::DEFAULT
468 }
469}
470#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
471#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
472#[cfg_attr(feature = "serde", serde(tag = "type"))]
473#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
474#[repr(u32)]
475#[doc = "Camera tracking status flags"]
476pub enum CameraTrackingStatusFlags {
477 #[doc = "Camera is not tracking"]
478 CAMERA_TRACKING_STATUS_FLAGS_IDLE = 0,
479 #[doc = "Camera is tracking"]
480 CAMERA_TRACKING_STATUS_FLAGS_ACTIVE = 1,
481 #[doc = "Camera tracking in error state"]
482 CAMERA_TRACKING_STATUS_FLAGS_ERROR = 2,
483}
484impl CameraTrackingStatusFlags {
485 pub const DEFAULT: Self = Self::CAMERA_TRACKING_STATUS_FLAGS_IDLE;
486}
487impl Default for CameraTrackingStatusFlags {
488 fn default() -> Self {
489 Self::DEFAULT
490 }
491}
492bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Camera tracking target data (shows where tracked target is within image)"] pub struct CameraTrackingTargetData : u8 { # [doc = "Target data embedded in image data (proprietary)"] const CAMERA_TRACKING_TARGET_DATA_EMBEDDED = 1 ; # [doc = "Target data rendered in image"] const CAMERA_TRACKING_TARGET_DATA_RENDERED = 2 ; # [doc = "Target data within status message (Point or Rectangle)"] const CAMERA_TRACKING_TARGET_DATA_IN_STATUS = 4 ; } }
493impl CameraTrackingTargetData {
494 pub const DEFAULT: Self = Self::CAMERA_TRACKING_TARGET_DATA_EMBEDDED;
495}
496impl Default for CameraTrackingTargetData {
497 fn default() -> Self {
498 Self::DEFAULT
499 }
500}
501#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
502#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
503#[cfg_attr(feature = "serde", serde(tag = "type"))]
504#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
505#[repr(u32)]
506#[doc = "Zoom types for MAV_CMD_SET_CAMERA_ZOOM"]
507pub enum CameraZoomType {
508 #[doc = "Zoom one step increment (-1 for wide, 1 for tele)"]
509 ZOOM_TYPE_STEP = 0,
510 #[doc = "Continuous normalized zoom in/out rate until stopped. Range -1..1, negative: wide, positive: narrow/tele, 0 to stop zooming. Other values should be clipped to the range."]
511 ZOOM_TYPE_CONTINUOUS = 1,
512 #[doc = "Zoom value as proportion of full camera range (a percentage value between 0.0 and 100.0)"]
513 ZOOM_TYPE_RANGE = 2,
514 #[doc = "Zoom value/variable focal length in millimetres. Note that there is no message to get the valid zoom range of the camera, so this can type can only be used for cameras where the zoom range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera)"]
515 ZOOM_TYPE_FOCAL_LENGTH = 3,
516 #[doc = "Zoom value as horizontal field of view in degrees."]
517 ZOOM_TYPE_HORIZONTAL_FOV = 4,
518}
519impl CameraZoomType {
520 pub const DEFAULT: Self = Self::ZOOM_TYPE_STEP;
521}
522impl Default for CameraZoomType {
523 fn default() -> Self {
524 Self::DEFAULT
525 }
526}
527#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
528#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
529#[cfg_attr(feature = "serde", serde(tag = "type"))]
530#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
531#[repr(u32)]
532pub enum CanFilterOp {
533 CAN_FILTER_REPLACE = 0,
534 CAN_FILTER_ADD = 1,
535 CAN_FILTER_REMOVE = 2,
536}
537impl CanFilterOp {
538 pub const DEFAULT: Self = Self::CAN_FILTER_REPLACE;
539}
540impl Default for CanFilterOp {
541 fn default() -> Self {
542 Self::DEFAULT
543 }
544}
545#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
546#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
547#[cfg_attr(feature = "serde", serde(tag = "type"))]
548#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
549#[repr(u32)]
550#[doc = "Possible responses from a CELLULAR_CONFIG message."]
551pub enum CellularConfigResponse {
552 #[doc = "Changes accepted."]
553 CELLULAR_CONFIG_RESPONSE_ACCEPTED = 0,
554 #[doc = "Invalid APN."]
555 CELLULAR_CONFIG_RESPONSE_APN_ERROR = 1,
556 #[doc = "Invalid PIN."]
557 CELLULAR_CONFIG_RESPONSE_PIN_ERROR = 2,
558 #[doc = "Changes rejected."]
559 CELLULAR_CONFIG_RESPONSE_REJECTED = 3,
560 #[doc = "PUK is required to unblock SIM card."]
561 CELLULAR_CONFIG_BLOCKED_PUK_REQUIRED = 4,
562}
563impl CellularConfigResponse {
564 pub const DEFAULT: Self = Self::CELLULAR_CONFIG_RESPONSE_ACCEPTED;
565}
566impl Default for CellularConfigResponse {
567 fn default() -> Self {
568 Self::DEFAULT
569 }
570}
571#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
572#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
573#[cfg_attr(feature = "serde", serde(tag = "type"))]
574#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
575#[repr(u32)]
576#[doc = "These flags are used to diagnose the failure state of CELLULAR_STATUS"]
577pub enum CellularNetworkFailedReason {
578 #[doc = "No error"]
579 CELLULAR_NETWORK_FAILED_REASON_NONE = 0,
580 #[doc = "Error state is unknown"]
581 CELLULAR_NETWORK_FAILED_REASON_UNKNOWN = 1,
582 #[doc = "SIM is required for the modem but missing"]
583 CELLULAR_NETWORK_FAILED_REASON_SIM_MISSING = 2,
584 #[doc = "SIM is available, but not usable for connection"]
585 CELLULAR_NETWORK_FAILED_REASON_SIM_ERROR = 3,
586}
587impl CellularNetworkFailedReason {
588 pub const DEFAULT: Self = Self::CELLULAR_NETWORK_FAILED_REASON_NONE;
589}
590impl Default for CellularNetworkFailedReason {
591 fn default() -> Self {
592 Self::DEFAULT
593 }
594}
595#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
596#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
597#[cfg_attr(feature = "serde", serde(tag = "type"))]
598#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
599#[repr(u32)]
600#[doc = "Cellular network radio type"]
601pub enum CellularNetworkRadioType {
602 CELLULAR_NETWORK_RADIO_TYPE_NONE = 0,
603 CELLULAR_NETWORK_RADIO_TYPE_GSM = 1,
604 CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2,
605 CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3,
606 CELLULAR_NETWORK_RADIO_TYPE_LTE = 4,
607}
608impl CellularNetworkRadioType {
609 pub const DEFAULT: Self = Self::CELLULAR_NETWORK_RADIO_TYPE_NONE;
610}
611impl Default for CellularNetworkRadioType {
612 fn default() -> Self {
613 Self::DEFAULT
614 }
615}
616#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
617#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
618#[cfg_attr(feature = "serde", serde(tag = "type"))]
619#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
620#[repr(u32)]
621#[doc = "These flags encode the cellular network status"]
622pub enum CellularStatusFlag {
623 #[doc = "State unknown or not reportable."]
624 CELLULAR_STATUS_FLAG_UNKNOWN = 0,
625 #[doc = "Modem is unusable"]
626 CELLULAR_STATUS_FLAG_FAILED = 1,
627 #[doc = "Modem is being initialized"]
628 CELLULAR_STATUS_FLAG_INITIALIZING = 2,
629 #[doc = "Modem is locked"]
630 CELLULAR_STATUS_FLAG_LOCKED = 3,
631 #[doc = "Modem is not enabled and is powered down"]
632 CELLULAR_STATUS_FLAG_DISABLED = 4,
633 #[doc = "Modem is currently transitioning to the CELLULAR_STATUS_FLAG_DISABLED state"]
634 CELLULAR_STATUS_FLAG_DISABLING = 5,
635 #[doc = "Modem is currently transitioning to the CELLULAR_STATUS_FLAG_ENABLED state"]
636 CELLULAR_STATUS_FLAG_ENABLING = 6,
637 #[doc = "Modem is enabled and powered on but not registered with a network provider and not available for data connections"]
638 CELLULAR_STATUS_FLAG_ENABLED = 7,
639 #[doc = "Modem is searching for a network provider to register"]
640 CELLULAR_STATUS_FLAG_SEARCHING = 8,
641 #[doc = "Modem is registered with a network provider, and data connections and messaging may be available for use"]
642 CELLULAR_STATUS_FLAG_REGISTERED = 9,
643 #[doc = "Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated"]
644 CELLULAR_STATUS_FLAG_DISCONNECTING = 10,
645 #[doc = "Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered"]
646 CELLULAR_STATUS_FLAG_CONNECTING = 11,
647 #[doc = "One or more packet data bearers is active and connected"]
648 CELLULAR_STATUS_FLAG_CONNECTED = 12,
649}
650impl CellularStatusFlag {
651 pub const DEFAULT: Self = Self::CELLULAR_STATUS_FLAG_UNKNOWN;
652}
653impl Default for CellularStatusFlag {
654 fn default() -> Self {
655 Self::DEFAULT
656 }
657}
658#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
659#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
660#[cfg_attr(feature = "serde", serde(tag = "type"))]
661#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
662#[repr(u32)]
663#[doc = "Supported component metadata types. These are used in the \"general\" metadata file returned by COMPONENT_METADATA to provide information about supported metadata types. The types are not used directly in MAVLink messages."]
664pub enum CompMetadataType {
665 #[doc = "General information about the component. General metadata includes information about other metadata types supported by the component. Files of this type must be supported, and must be downloadable from vehicle using a MAVLink FTP URI."]
666 COMP_METADATA_TYPE_GENERAL = 0,
667 #[doc = "Parameter meta data."]
668 COMP_METADATA_TYPE_PARAMETER = 1,
669 #[doc = "Meta data that specifies which commands and command parameters the vehicle supports. (WIP)"]
670 COMP_METADATA_TYPE_COMMANDS = 2,
671 #[doc = "Meta data that specifies external non-MAVLink peripherals."]
672 COMP_METADATA_TYPE_PERIPHERALS = 3,
673 #[doc = "Meta data for the events interface."]
674 COMP_METADATA_TYPE_EVENTS = 4,
675 #[doc = "Meta data for actuator configuration (motors, servos and vehicle geometry) and testing."]
676 COMP_METADATA_TYPE_ACTUATORS = 5,
677}
678impl CompMetadataType {
679 pub const DEFAULT: Self = Self::COMP_METADATA_TYPE_GENERAL;
680}
681impl Default for CompMetadataType {
682 fn default() -> Self {
683 Self::DEFAULT
684 }
685}
686#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
687#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
688#[cfg_attr(feature = "serde", serde(tag = "type"))]
689#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
690#[repr(u32)]
691#[doc = "Indicates the ESC connection type."]
692pub enum EscConnectionType {
693 #[doc = "Traditional PPM ESC."]
694 ESC_CONNECTION_TYPE_PPM = 0,
695 #[doc = "Serial Bus connected ESC."]
696 ESC_CONNECTION_TYPE_SERIAL = 1,
697 #[doc = "One Shot PPM ESC."]
698 ESC_CONNECTION_TYPE_ONESHOT = 2,
699 #[doc = "I2C ESC."]
700 ESC_CONNECTION_TYPE_I2C = 3,
701 #[doc = "CAN-Bus ESC."]
702 ESC_CONNECTION_TYPE_CAN = 4,
703 #[doc = "DShot ESC."]
704 ESC_CONNECTION_TYPE_DSHOT = 5,
705}
706impl EscConnectionType {
707 pub const DEFAULT: Self = Self::ESC_CONNECTION_TYPE_PPM;
708}
709impl Default for EscConnectionType {
710 fn default() -> Self {
711 Self::DEFAULT
712 }
713}
714bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to report ESC failures."] pub struct EscFailureFlags : u16 { # [doc = "Over current failure."] const ESC_FAILURE_OVER_CURRENT = 1 ; # [doc = "Over voltage failure."] const ESC_FAILURE_OVER_VOLTAGE = 2 ; # [doc = "Over temperature failure."] const ESC_FAILURE_OVER_TEMPERATURE = 4 ; # [doc = "Over RPM failure."] const ESC_FAILURE_OVER_RPM = 8 ; # [doc = "Inconsistent command failure i.e. out of bounds."] const ESC_FAILURE_INCONSISTENT_CMD = 16 ; # [doc = "Motor stuck failure."] const ESC_FAILURE_MOTOR_STUCK = 32 ; # [doc = "Generic ESC failure."] const ESC_FAILURE_GENERIC = 64 ; } }
715impl EscFailureFlags {
716 pub const DEFAULT: Self = Self::ESC_FAILURE_OVER_CURRENT;
717}
718impl Default for EscFailureFlags {
719 fn default() -> Self {
720 Self::DEFAULT
721 }
722}
723bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags in ESTIMATOR_STATUS message"] pub struct EstimatorStatusFlags : u16 { # [doc = "True if the attitude estimate is good"] const ESTIMATOR_ATTITUDE = 1 ; # [doc = "True if the horizontal velocity estimate is good"] const ESTIMATOR_VELOCITY_HORIZ = 2 ; # [doc = "True if the vertical velocity estimate is good"] const ESTIMATOR_VELOCITY_VERT = 4 ; # [doc = "True if the horizontal position (relative) estimate is good"] const ESTIMATOR_POS_HORIZ_REL = 8 ; # [doc = "True if the horizontal position (absolute) estimate is good"] const ESTIMATOR_POS_HORIZ_ABS = 16 ; # [doc = "True if the vertical position (absolute) estimate is good"] const ESTIMATOR_POS_VERT_ABS = 32 ; # [doc = "True if the vertical position (above ground) estimate is good"] const ESTIMATOR_POS_VERT_AGL = 64 ; # [doc = "True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow)"] const ESTIMATOR_CONST_POS_MODE = 128 ; # [doc = "True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate"] const ESTIMATOR_PRED_POS_HORIZ_REL = 256 ; # [doc = "True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate"] const ESTIMATOR_PRED_POS_HORIZ_ABS = 512 ; # [doc = "True if the EKF has detected a GPS glitch"] const ESTIMATOR_GPS_GLITCH = 1024 ; # [doc = "True if the EKF has detected bad accelerometer data"] const ESTIMATOR_ACCEL_ERROR = 2048 ; } }
724impl EstimatorStatusFlags {
725 pub const DEFAULT: Self = Self::ESTIMATOR_ATTITUDE;
726}
727impl Default for EstimatorStatusFlags {
728 fn default() -> Self {
729 Self::DEFAULT
730 }
731}
732#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
733#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
734#[cfg_attr(feature = "serde", serde(tag = "type"))]
735#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
736#[repr(u32)]
737#[doc = "List of possible failure type to inject."]
738pub enum FailureType {
739 #[doc = "No failure injected, used to reset a previous failure."]
740 FAILURE_TYPE_OK = 0,
741 #[doc = "Sets unit off, so completely non-responsive."]
742 FAILURE_TYPE_OFF = 1,
743 #[doc = "Unit is stuck e.g. keeps reporting the same value."]
744 FAILURE_TYPE_STUCK = 2,
745 #[doc = "Unit is reporting complete garbage."]
746 FAILURE_TYPE_GARBAGE = 3,
747 #[doc = "Unit is consistently wrong."]
748 FAILURE_TYPE_WRONG = 4,
749 #[doc = "Unit is slow, so e.g. reporting at slower than expected rate."]
750 FAILURE_TYPE_SLOW = 5,
751 #[doc = "Data of unit is delayed in time."]
752 FAILURE_TYPE_DELAYED = 6,
753 #[doc = "Unit is sometimes working, sometimes not."]
754 FAILURE_TYPE_INTERMITTENT = 7,
755}
756impl FailureType {
757 pub const DEFAULT: Self = Self::FAILURE_TYPE_OK;
758}
759impl Default for FailureType {
760 fn default() -> Self {
761 Self::DEFAULT
762 }
763}
764#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
765#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
766#[cfg_attr(feature = "serde", serde(tag = "type"))]
767#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
768#[repr(u32)]
769#[doc = "List of possible units where failures can be injected."]
770pub enum FailureUnit {
771 FAILURE_UNIT_SENSOR_GYRO = 0,
772 FAILURE_UNIT_SENSOR_ACCEL = 1,
773 FAILURE_UNIT_SENSOR_MAG = 2,
774 FAILURE_UNIT_SENSOR_BARO = 3,
775 FAILURE_UNIT_SENSOR_GPS = 4,
776 FAILURE_UNIT_SENSOR_OPTICAL_FLOW = 5,
777 FAILURE_UNIT_SENSOR_VIO = 6,
778 FAILURE_UNIT_SENSOR_DISTANCE_SENSOR = 7,
779 FAILURE_UNIT_SENSOR_AIRSPEED = 8,
780 FAILURE_UNIT_SYSTEM_BATTERY = 100,
781 FAILURE_UNIT_SYSTEM_MOTOR = 101,
782 FAILURE_UNIT_SYSTEM_SERVO = 102,
783 FAILURE_UNIT_SYSTEM_AVOIDANCE = 103,
784 FAILURE_UNIT_SYSTEM_RC_SIGNAL = 104,
785 FAILURE_UNIT_SYSTEM_MAVLINK_SIGNAL = 105,
786}
787impl FailureUnit {
788 pub const DEFAULT: Self = Self::FAILURE_UNIT_SENSOR_GYRO;
789}
790impl Default for FailureUnit {
791 fn default() -> Self {
792 Self::DEFAULT
793 }
794}
795#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
796#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
797#[cfg_attr(feature = "serde", serde(tag = "type"))]
798#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
799#[repr(u32)]
800pub enum FenceBreach {
801 #[doc = "No last fence breach"]
802 FENCE_BREACH_NONE = 0,
803 #[doc = "Breached minimum altitude"]
804 FENCE_BREACH_MINALT = 1,
805 #[doc = "Breached maximum altitude"]
806 FENCE_BREACH_MAXALT = 2,
807 #[doc = "Breached fence boundary"]
808 FENCE_BREACH_BOUNDARY = 3,
809}
810impl FenceBreach {
811 pub const DEFAULT: Self = Self::FENCE_BREACH_NONE;
812}
813impl Default for FenceBreach {
814 fn default() -> Self {
815 Self::DEFAULT
816 }
817}
818#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
819#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
820#[cfg_attr(feature = "serde", serde(tag = "type"))]
821#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
822#[repr(u32)]
823#[doc = "Actions being taken to mitigate/prevent fence breach"]
824pub enum FenceMitigate {
825 #[doc = "Unknown"]
826 FENCE_MITIGATE_UNKNOWN = 0,
827 #[doc = "No actions being taken"]
828 FENCE_MITIGATE_NONE = 1,
829 #[doc = "Velocity limiting active to prevent breach"]
830 FENCE_MITIGATE_VEL_LIMIT = 2,
831}
832impl FenceMitigate {
833 pub const DEFAULT: Self = Self::FENCE_MITIGATE_UNKNOWN;
834}
835impl Default for FenceMitigate {
836 fn default() -> Self {
837 Self::DEFAULT
838 }
839}
840#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
841#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
842#[cfg_attr(feature = "serde", serde(tag = "type"))]
843#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
844#[repr(u32)]
845#[doc = "Fence types to enable or disable when using MAV_CMD_DO_FENCE_ENABLE. Note that at least one of these flags must be set in MAV_CMD_DO_FENCE_ENABLE.param2. If none are set, the flight stack will ignore the field and enable/disable its default set of fences (usually all of them)."]
846pub enum FenceType {
847 #[doc = "Maximum altitude fence"]
848 FENCE_TYPE_ALT_MAX = 1,
849 #[doc = "Circle fence"]
850 FENCE_TYPE_CIRCLE = 2,
851 #[doc = "Polygon fence"]
852 FENCE_TYPE_POLYGON = 4,
853 #[doc = "Minimum altitude fence"]
854 FENCE_TYPE_ALT_MIN = 8,
855}
856impl FenceType {
857 pub const DEFAULT: Self = Self::FENCE_TYPE_ALT_MAX;
858}
859impl Default for FenceType {
860 fn default() -> Self {
861 Self::DEFAULT
862 }
863}
864#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
865#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
866#[cfg_attr(feature = "serde", serde(tag = "type"))]
867#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
868#[repr(u32)]
869#[doc = "These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65."]
870pub enum FirmwareVersionType {
871 #[doc = "development release"]
872 FIRMWARE_VERSION_TYPE_DEV = 0,
873 #[doc = "alpha release"]
874 FIRMWARE_VERSION_TYPE_ALPHA = 64,
875 #[doc = "beta release"]
876 FIRMWARE_VERSION_TYPE_BETA = 128,
877 #[doc = "release candidate"]
878 FIRMWARE_VERSION_TYPE_RC = 192,
879 #[doc = "official stable release"]
880 FIRMWARE_VERSION_TYPE_OFFICIAL = 255,
881}
882impl FirmwareVersionType {
883 pub const DEFAULT: Self = Self::FIRMWARE_VERSION_TYPE_DEV;
884}
885impl Default for FirmwareVersionType {
886 fn default() -> Self {
887 Self::DEFAULT
888 }
889}
890bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Gimbal device (low level) capability flags (bitmap)."] pub struct GimbalDeviceCapFlags : u16 { # [doc = "Gimbal device supports a retracted position."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT = 1 ; # [doc = "Gimbal device supports a horizontal, forward looking position, stabilized."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL = 2 ; # [doc = "Gimbal device supports rotating around roll axis."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS = 4 ; # [doc = "Gimbal device supports to follow a roll angle relative to the vehicle."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW = 8 ; # [doc = "Gimbal device supports locking to a roll angle (generally that's the default with roll stabilized)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK = 16 ; # [doc = "Gimbal device supports rotating around pitch axis."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS = 32 ; # [doc = "Gimbal device supports to follow a pitch angle relative to the vehicle."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW = 64 ; # [doc = "Gimbal device supports locking to a pitch angle (generally that's the default with pitch stabilized)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK = 128 ; # [doc = "Gimbal device supports rotating around yaw axis."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS = 256 ; # [doc = "Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW = 512 ; # [doc = "Gimbal device supports locking to an absolute heading, i.e., yaw angle relative to North (earth frame, often this is an option available)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK = 1024 ; # [doc = "Gimbal device supports yawing/panning infinitely (e.g. using slip disk)."] const GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW = 2048 ; # [doc = "Gimbal device supports yaw angles and angular velocities relative to North (earth frame). This usually requires support by an autopilot via AUTOPILOT_STATE_FOR_GIMBAL_DEVICE. Support can go on and off during runtime, which is reported by the flag GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_IN_EARTH_FRAME."] const GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME = 4096 ; # [doc = "Gimbal device supports radio control inputs as an alternative input for controlling the gimbal orientation."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS = 8192 ; } }
891impl GimbalDeviceCapFlags {
892 pub const DEFAULT: Self = Self::GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT;
893}
894impl Default for GimbalDeviceCapFlags {
895 fn default() -> Self {
896 Self::DEFAULT
897 }
898}
899bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Gimbal device (low level) error flags (bitmap, 0 means no error)"] pub struct GimbalDeviceErrorFlags : u32 { # [doc = "Gimbal device is limited by hardware roll limit."] const GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT = 1 ; # [doc = "Gimbal device is limited by hardware pitch limit."] const GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT = 2 ; # [doc = "Gimbal device is limited by hardware yaw limit."] const GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT = 4 ; # [doc = "There is an error with the gimbal encoders."] const GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR = 8 ; # [doc = "There is an error with the gimbal power source."] const GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR = 16 ; # [doc = "There is an error with the gimbal motors."] const GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR = 32 ; # [doc = "There is an error with the gimbal's software."] const GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR = 64 ; # [doc = "There is an error with the gimbal's communication."] const GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR = 128 ; # [doc = "Gimbal device is currently calibrating."] const GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING = 256 ; # [doc = "Gimbal device is not assigned to a gimbal manager."] const GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER = 512 ; } }
900impl GimbalDeviceErrorFlags {
901 pub const DEFAULT: Self = Self::GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT;
902}
903impl Default for GimbalDeviceErrorFlags {
904 fn default() -> Self {
905 Self::DEFAULT
906 }
907}
908bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags for gimbal device (lower level) operation."] pub struct GimbalDeviceFlags : u16 { # [doc = "Set to retracted safe position (no stabilization), takes precedence over all other flags."] const GIMBAL_DEVICE_FLAGS_RETRACT = 1 ; # [doc = "Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (roll=pitch=yaw=0) but may be any orientation."] const GIMBAL_DEVICE_FLAGS_NEUTRAL = 2 ; # [doc = "Lock roll angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal."] const GIMBAL_DEVICE_FLAGS_ROLL_LOCK = 4 ; # [doc = "Lock pitch angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal."] const GIMBAL_DEVICE_FLAGS_PITCH_LOCK = 8 ; # [doc = "Lock yaw angle to absolute angle relative to North (not relative to vehicle). If this flag is set, the yaw angle and z component of angular velocity are relative to North (earth frame, x-axis pointing North), else they are relative to the vehicle heading (vehicle frame, earth frame rotated so that the x-axis is pointing forward)."] const GIMBAL_DEVICE_FLAGS_YAW_LOCK = 16 ; # [doc = "Yaw angle and z component of angular velocity are relative to the vehicle heading (vehicle frame, earth frame rotated such that the x-axis is pointing forward)."] const GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME = 32 ; # [doc = "Yaw angle and z component of angular velocity are relative to North (earth frame, x-axis is pointing North)."] const GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME = 64 ; # [doc = "Gimbal device can accept yaw angle inputs relative to North (earth frame). This flag is only for reporting (attempts to set this flag are ignored)."] const GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = 128 ; # [doc = "The gimbal orientation is set exclusively by the RC signals feed to the gimbal's radio control inputs. MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE) are ignored."] const GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE = 256 ; # [doc = "The gimbal orientation is determined by combining/mixing the RC signals feed to the gimbal's radio control inputs and the MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE). How these two controls are combined or mixed is not defined by the protocol but is up to the implementation."] const GIMBAL_DEVICE_FLAGS_RC_MIXED = 512 ; } }
909impl GimbalDeviceFlags {
910 pub const DEFAULT: Self = Self::GIMBAL_DEVICE_FLAGS_RETRACT;
911}
912impl Default for GimbalDeviceFlags {
913 fn default() -> Self {
914 Self::DEFAULT
915 }
916}
917bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Gimbal manager high level capability flags (bitmap). The first 16 bits are identical to the GIMBAL_DEVICE_CAP_FLAGS. However, the gimbal manager does not need to copy the flags from the gimbal but can also enhance the capabilities and thus add flags."] pub struct GimbalManagerCapFlags : u32 { # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT = 1 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL = 2 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS = 4 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOW = 8 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCK = 16 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS = 32 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOW = 64 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCK = 128 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS = 256 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW = 512 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK = 1024 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW."] const GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_INFINITE_YAW = 2048 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME."] const GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME = 4096 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_RC_INPUTS = 8192 ; # [doc = "Gimbal manager supports to point to a local position."] const GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCAL = 65536 ; # [doc = "Gimbal manager supports to point to a global latitude, longitude, altitude position."] const GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL = 131072 ; } }
918impl GimbalManagerCapFlags {
919 pub const DEFAULT: Self = Self::GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT;
920}
921impl Default for GimbalManagerCapFlags {
922 fn default() -> Self {
923 Self::DEFAULT
924 }
925}
926bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags for high level gimbal manager operation The first 16 bits are identical to the GIMBAL_DEVICE_FLAGS."] pub struct GimbalManagerFlags : u32 { # [doc = "Based on GIMBAL_DEVICE_FLAGS_RETRACT."] const GIMBAL_MANAGER_FLAGS_RETRACT = 1 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_NEUTRAL."] const GIMBAL_MANAGER_FLAGS_NEUTRAL = 2 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK."] const GIMBAL_MANAGER_FLAGS_ROLL_LOCK = 4 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK."] const GIMBAL_MANAGER_FLAGS_PITCH_LOCK = 8 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK."] const GIMBAL_MANAGER_FLAGS_YAW_LOCK = 16 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME."] const GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME = 32 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME."] const GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME = 64 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME."] const GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = 128 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE."] const GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE = 256 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_RC_MIXED."] const GIMBAL_MANAGER_FLAGS_RC_MIXED = 512 ; } }
927impl GimbalManagerFlags {
928 pub const DEFAULT: Self = Self::GIMBAL_MANAGER_FLAGS_RETRACT;
929}
930impl Default for GimbalManagerFlags {
931 fn default() -> Self {
932 Self::DEFAULT
933 }
934}
935#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
936#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
937#[cfg_attr(feature = "serde", serde(tag = "type"))]
938#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
939#[repr(u32)]
940#[doc = "Type of GPS fix"]
941pub enum GpsFixType {
942 #[doc = "No GPS connected"]
943 GPS_FIX_TYPE_NO_GPS = 0,
944 #[doc = "No position information, GPS is connected"]
945 GPS_FIX_TYPE_NO_FIX = 1,
946 #[doc = "2D position"]
947 GPS_FIX_TYPE_2D_FIX = 2,
948 #[doc = "3D position"]
949 GPS_FIX_TYPE_3D_FIX = 3,
950 #[doc = "DGPS/SBAS aided 3D position"]
951 GPS_FIX_TYPE_DGPS = 4,
952 #[doc = "RTK float, 3D position"]
953 GPS_FIX_TYPE_RTK_FLOAT = 5,
954 #[doc = "RTK Fixed, 3D position"]
955 GPS_FIX_TYPE_RTK_FIXED = 6,
956 #[doc = "Static fixed, typically used for base stations"]
957 GPS_FIX_TYPE_STATIC = 7,
958 #[doc = "PPP, 3D position."]
959 GPS_FIX_TYPE_PPP = 8,
960}
961impl GpsFixType {
962 pub const DEFAULT: Self = Self::GPS_FIX_TYPE_NO_GPS;
963}
964impl Default for GpsFixType {
965 fn default() -> Self {
966 Self::DEFAULT
967 }
968}
969bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] pub struct GpsInputIgnoreFlags : u16 { # [doc = "ignore altitude field"] const GPS_INPUT_IGNORE_FLAG_ALT = 1 ; # [doc = "ignore hdop field"] const GPS_INPUT_IGNORE_FLAG_HDOP = 2 ; # [doc = "ignore vdop field"] const GPS_INPUT_IGNORE_FLAG_VDOP = 4 ; # [doc = "ignore horizontal velocity field (vn and ve)"] const GPS_INPUT_IGNORE_FLAG_VEL_HORIZ = 8 ; # [doc = "ignore vertical velocity field (vd)"] const GPS_INPUT_IGNORE_FLAG_VEL_VERT = 16 ; # [doc = "ignore speed accuracy field"] const GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY = 32 ; # [doc = "ignore horizontal accuracy field"] const GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY = 64 ; # [doc = "ignore vertical accuracy field"] const GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY = 128 ; } }
970impl GpsInputIgnoreFlags {
971 pub const DEFAULT: Self = Self::GPS_INPUT_IGNORE_FLAG_ALT;
972}
973impl Default for GpsInputIgnoreFlags {
974 fn default() -> Self {
975 Self::DEFAULT
976 }
977}
978#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
979#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
980#[cfg_attr(feature = "serde", serde(tag = "type"))]
981#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
982#[repr(u32)]
983#[doc = "Gripper actions."]
984pub enum GripperActions {
985 #[doc = "Gripper release cargo."]
986 GRIPPER_ACTION_RELEASE = 0,
987 #[doc = "Gripper grab onto cargo."]
988 GRIPPER_ACTION_GRAB = 1,
989}
990impl GripperActions {
991 pub const DEFAULT: Self = Self::GRIPPER_ACTION_RELEASE;
992}
993impl Default for GripperActions {
994 fn default() -> Self {
995 Self::DEFAULT
996 }
997}
998bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags in the HIGHRES_IMU message indicate which fields have updated since the last message"] pub struct HighresImuUpdatedFlags : u16 { # [doc = "The value in the xacc field has been updated"] const HIGHRES_IMU_UPDATED_XACC = 1 ; # [doc = "The value in the yacc field has been updated"] const HIGHRES_IMU_UPDATED_YACC = 2 ; # [doc = "The value in the zacc field has been updated since"] const HIGHRES_IMU_UPDATED_ZACC = 4 ; # [doc = "The value in the xgyro field has been updated"] const HIGHRES_IMU_UPDATED_XGYRO = 8 ; # [doc = "The value in the ygyro field has been updated"] const HIGHRES_IMU_UPDATED_YGYRO = 16 ; # [doc = "The value in the zgyro field has been updated"] const HIGHRES_IMU_UPDATED_ZGYRO = 32 ; # [doc = "The value in the xmag field has been updated"] const HIGHRES_IMU_UPDATED_XMAG = 64 ; # [doc = "The value in the ymag field has been updated"] const HIGHRES_IMU_UPDATED_YMAG = 128 ; # [doc = "The value in the zmag field has been updated"] const HIGHRES_IMU_UPDATED_ZMAG = 256 ; # [doc = "The value in the abs_pressure field has been updated"] const HIGHRES_IMU_UPDATED_ABS_PRESSURE = 512 ; # [doc = "The value in the diff_pressure field has been updated"] const HIGHRES_IMU_UPDATED_DIFF_PRESSURE = 1024 ; # [doc = "The value in the pressure_alt field has been updated"] const HIGHRES_IMU_UPDATED_PRESSURE_ALT = 2048 ; # [doc = "The value in the temperature field has been updated"] const HIGHRES_IMU_UPDATED_TEMPERATURE = 4096 ; } }
999impl HighresImuUpdatedFlags {
1000 pub const DEFAULT: Self = Self::HIGHRES_IMU_UPDATED_XACC;
1001}
1002impl Default for HighresImuUpdatedFlags {
1003 fn default() -> Self {
1004 Self::DEFAULT
1005 }
1006}
1007bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags used in HIL_ACTUATOR_CONTROLS message."] pub struct HilActuatorControlsFlags : u64 { # [doc = "Simulation is using lockstep"] const HIL_ACTUATOR_CONTROLS_FLAGS_LOCKSTEP = 1 ; } }
1008impl HilActuatorControlsFlags {
1009 pub const DEFAULT: Self = Self::HIL_ACTUATOR_CONTROLS_FLAGS_LOCKSTEP;
1010}
1011impl Default for HilActuatorControlsFlags {
1012 fn default() -> Self {
1013 Self::DEFAULT
1014 }
1015}
1016bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags in the HIL_SENSOR message indicate which fields have updated since the last message"] pub struct HilSensorUpdatedFlags : u32 { # [doc = "The value in the xacc field has been updated"] const HIL_SENSOR_UPDATED_XACC = 1 ; # [doc = "The value in the yacc field has been updated"] const HIL_SENSOR_UPDATED_YACC = 2 ; # [doc = "The value in the zacc field has been updated"] const HIL_SENSOR_UPDATED_ZACC = 4 ; # [doc = "The value in the xgyro field has been updated"] const HIL_SENSOR_UPDATED_XGYRO = 8 ; # [doc = "The value in the ygyro field has been updated"] const HIL_SENSOR_UPDATED_YGYRO = 16 ; # [doc = "The value in the zgyro field has been updated"] const HIL_SENSOR_UPDATED_ZGYRO = 32 ; # [doc = "The value in the xmag field has been updated"] const HIL_SENSOR_UPDATED_XMAG = 64 ; # [doc = "The value in the ymag field has been updated"] const HIL_SENSOR_UPDATED_YMAG = 128 ; # [doc = "The value in the zmag field has been updated"] const HIL_SENSOR_UPDATED_ZMAG = 256 ; # [doc = "The value in the abs_pressure field has been updated"] const HIL_SENSOR_UPDATED_ABS_PRESSURE = 512 ; # [doc = "The value in the diff_pressure field has been updated"] const HIL_SENSOR_UPDATED_DIFF_PRESSURE = 1024 ; # [doc = "The value in the pressure_alt field has been updated"] const HIL_SENSOR_UPDATED_PRESSURE_ALT = 2048 ; # [doc = "The value in the temperature field has been updated"] const HIL_SENSOR_UPDATED_TEMPERATURE = 4096 ; # [doc = "Full reset of attitude/position/velocities/etc was performed in sim (Bit 31)."] const HIL_SENSOR_UPDATED_RESET = 2147483648 ; } }
1017impl HilSensorUpdatedFlags {
1018 pub const DEFAULT: Self = Self::HIL_SENSOR_UPDATED_XACC;
1019}
1020impl Default for HilSensorUpdatedFlags {
1021 fn default() -> Self {
1022 Self::DEFAULT
1023 }
1024}
1025bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to report failure cases over the high latency telemetry."] pub struct HlFailureFlag : u16 { # [doc = "GPS failure."] const HL_FAILURE_FLAG_GPS = 1 ; # [doc = "Differential pressure sensor failure."] const HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE = 2 ; # [doc = "Absolute pressure sensor failure."] const HL_FAILURE_FLAG_ABSOLUTE_PRESSURE = 4 ; # [doc = "Accelerometer sensor failure."] const HL_FAILURE_FLAG_3D_ACCEL = 8 ; # [doc = "Gyroscope sensor failure."] const HL_FAILURE_FLAG_3D_GYRO = 16 ; # [doc = "Magnetometer sensor failure."] const HL_FAILURE_FLAG_3D_MAG = 32 ; # [doc = "Terrain subsystem failure."] const HL_FAILURE_FLAG_TERRAIN = 64 ; # [doc = "Battery failure/critical low battery."] const HL_FAILURE_FLAG_BATTERY = 128 ; # [doc = "RC receiver failure/no RC connection."] const HL_FAILURE_FLAG_RC_RECEIVER = 256 ; # [doc = "Offboard link failure."] const HL_FAILURE_FLAG_OFFBOARD_LINK = 512 ; # [doc = "Engine failure."] const HL_FAILURE_FLAG_ENGINE = 1024 ; # [doc = "Geofence violation."] const HL_FAILURE_FLAG_GEOFENCE = 2048 ; # [doc = "Estimator failure, for example measurement rejection or large variances."] const HL_FAILURE_FLAG_ESTIMATOR = 4096 ; # [doc = "Mission failure."] const HL_FAILURE_FLAG_MISSION = 8192 ; } }
1026impl HlFailureFlag {
1027 pub const DEFAULT: Self = Self::HL_FAILURE_FLAG_GPS;
1028}
1029impl Default for HlFailureFlag {
1030 fn default() -> Self {
1031 Self::DEFAULT
1032 }
1033}
1034bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Illuminator module error flags (bitmap, 0 means no error)"] pub struct IlluminatorErrorFlags : u32 { # [doc = "Illuminator thermal throttling error."] const ILLUMINATOR_ERROR_FLAGS_THERMAL_THROTTLING = 1 ; # [doc = "Illuminator over temperature shutdown error."] const ILLUMINATOR_ERROR_FLAGS_OVER_TEMPERATURE_SHUTDOWN = 2 ; # [doc = "Illuminator thermistor failure."] const ILLUMINATOR_ERROR_FLAGS_THERMISTOR_FAILURE = 4 ; } }
1035impl IlluminatorErrorFlags {
1036 pub const DEFAULT: Self = Self::ILLUMINATOR_ERROR_FLAGS_THERMAL_THROTTLING;
1037}
1038impl Default for IlluminatorErrorFlags {
1039 fn default() -> Self {
1040 Self::DEFAULT
1041 }
1042}
1043#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1044#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1045#[cfg_attr(feature = "serde", serde(tag = "type"))]
1046#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1047#[repr(u32)]
1048#[doc = "Modes of illuminator"]
1049pub enum IlluminatorMode {
1050 #[doc = "Illuminator mode is not specified/unknown"]
1051 ILLUMINATOR_MODE_UNKNOWN = 0,
1052 #[doc = "Illuminator behavior is controlled by MAV_CMD_DO_ILLUMINATOR_CONFIGURE settings"]
1053 ILLUMINATOR_MODE_INTERNAL_CONTROL = 1,
1054 #[doc = "Illuminator behavior is controlled by external factors: e.g. an external hardware signal"]
1055 ILLUMINATOR_MODE_EXTERNAL_SYNC = 2,
1056}
1057impl IlluminatorMode {
1058 pub const DEFAULT: Self = Self::ILLUMINATOR_MODE_UNKNOWN;
1059}
1060impl Default for IlluminatorMode {
1061 fn default() -> Self {
1062 Self::DEFAULT
1063 }
1064}
1065#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1066#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1067#[cfg_attr(feature = "serde", serde(tag = "type"))]
1068#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1069#[repr(u32)]
1070#[doc = "Type of landing target"]
1071pub enum LandingTargetType {
1072 #[doc = "Landing target signaled by light beacon (ex: IR-LOCK)"]
1073 LANDING_TARGET_TYPE_LIGHT_BEACON = 0,
1074 #[doc = "Landing target signaled by radio beacon (ex: ILS, NDB)"]
1075 LANDING_TARGET_TYPE_RADIO_BEACON = 1,
1076 #[doc = "Landing target represented by a fiducial marker (ex: ARTag)"]
1077 LANDING_TARGET_TYPE_VISION_FIDUCIAL = 2,
1078 #[doc = "Landing target represented by a pre-defined visual shape/feature (ex: X-marker, H-marker, square)"]
1079 LANDING_TARGET_TYPE_VISION_OTHER = 3,
1080}
1081impl LandingTargetType {
1082 pub const DEFAULT: Self = Self::LANDING_TARGET_TYPE_LIGHT_BEACON;
1083}
1084impl Default for LandingTargetType {
1085 fn default() -> Self {
1086 Self::DEFAULT
1087 }
1088}
1089#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1090#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1091#[cfg_attr(feature = "serde", serde(tag = "type"))]
1092#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1093#[repr(u32)]
1094pub enum MagCalStatus {
1095 MAG_CAL_NOT_STARTED = 0,
1096 MAG_CAL_WAITING_TO_START = 1,
1097 MAG_CAL_RUNNING_STEP_ONE = 2,
1098 MAG_CAL_RUNNING_STEP_TWO = 3,
1099 MAG_CAL_SUCCESS = 4,
1100 MAG_CAL_FAILED = 5,
1101 MAG_CAL_BAD_ORIENTATION = 6,
1102 MAG_CAL_BAD_RADIUS = 7,
1103}
1104impl MagCalStatus {
1105 pub const DEFAULT: Self = Self::MAG_CAL_NOT_STARTED;
1106}
1107impl Default for MagCalStatus {
1108 fn default() -> Self {
1109 Self::DEFAULT
1110 }
1111}
1112#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1113#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1114#[cfg_attr(feature = "serde", serde(tag = "type"))]
1115#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1116#[repr(u32)]
1117pub enum MavArmAuthDeniedReason {
1118 #[doc = "Not a specific reason"]
1119 MAV_ARM_AUTH_DENIED_REASON_GENERIC = 0,
1120 #[doc = "Authorizer will send the error as string to GCS"]
1121 MAV_ARM_AUTH_DENIED_REASON_NONE = 1,
1122 #[doc = "At least one waypoint have a invalid value"]
1123 MAV_ARM_AUTH_DENIED_REASON_INVALID_WAYPOINT = 2,
1124 #[doc = "Timeout in the authorizer process(in case it depends on network)"]
1125 MAV_ARM_AUTH_DENIED_REASON_TIMEOUT = 3,
1126 #[doc = "Airspace of the mission in use by another vehicle, second result parameter can have the waypoint id that caused it to be denied."]
1127 MAV_ARM_AUTH_DENIED_REASON_AIRSPACE_IN_USE = 4,
1128 #[doc = "Weather is not good to fly"]
1129 MAV_ARM_AUTH_DENIED_REASON_BAD_WEATHER = 5,
1130}
1131impl MavArmAuthDeniedReason {
1132 pub const DEFAULT: Self = Self::MAV_ARM_AUTH_DENIED_REASON_GENERIC;
1133}
1134impl Default for MavArmAuthDeniedReason {
1135 fn default() -> Self {
1136 Self::DEFAULT
1137 }
1138}
1139#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1140#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1141#[cfg_attr(feature = "serde", serde(tag = "type"))]
1142#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1143#[repr(u32)]
1144#[doc = "Micro air vehicle / autopilot classes. This identifies the individual model."]
1145pub enum MavAutopilot {
1146 #[doc = "Generic autopilot, full support for everything"]
1147 MAV_AUTOPILOT_GENERIC = 0,
1148 #[doc = "Reserved for future use."]
1149 MAV_AUTOPILOT_RESERVED = 1,
1150 #[doc = "SLUGS autopilot, <http://slugsuav.soe.ucsc.edu>"]
1151 MAV_AUTOPILOT_SLUGS = 2,
1152 #[doc = "ArduPilot - Plane/Copter/Rover/Sub/Tracker, <https://ardupilot.org>"]
1153 MAV_AUTOPILOT_ARDUPILOTMEGA = 3,
1154 #[doc = "OpenPilot, <http://openpilot.org>"]
1155 MAV_AUTOPILOT_OPENPILOT = 4,
1156 #[doc = "Generic autopilot only supporting simple waypoints"]
1157 MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY = 5,
1158 #[doc = "Generic autopilot supporting waypoints and other simple navigation commands"]
1159 MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY = 6,
1160 #[doc = "Generic autopilot supporting the full mission command set"]
1161 MAV_AUTOPILOT_GENERIC_MISSION_FULL = 7,
1162 #[doc = "No valid autopilot, e.g. a GCS or other MAVLink component"]
1163 MAV_AUTOPILOT_INVALID = 8,
1164 #[doc = "PPZ UAV - <http://nongnu.org/paparazzi>"]
1165 MAV_AUTOPILOT_PPZ = 9,
1166 #[doc = "UAV Dev Board"]
1167 MAV_AUTOPILOT_UDB = 10,
1168 #[doc = "FlexiPilot"]
1169 MAV_AUTOPILOT_FP = 11,
1170 #[doc = "PX4 Autopilot - <http://px4.io/>"]
1171 MAV_AUTOPILOT_PX4 = 12,
1172 #[doc = "SMACCMPilot - <http://smaccmpilot.org>"]
1173 MAV_AUTOPILOT_SMACCMPILOT = 13,
1174 #[doc = "AutoQuad -- <http://autoquad.org>"]
1175 MAV_AUTOPILOT_AUTOQUAD = 14,
1176 #[doc = "Armazila -- <http://armazila.com>"]
1177 MAV_AUTOPILOT_ARMAZILA = 15,
1178 #[doc = "Aerob -- <http://aerob.ru>"]
1179 MAV_AUTOPILOT_AEROB = 16,
1180 #[doc = "ASLUAV autopilot -- <http://www.asl.ethz.ch>"]
1181 MAV_AUTOPILOT_ASLUAV = 17,
1182 #[doc = "SmartAP Autopilot - <http://sky-drones.com>"]
1183 MAV_AUTOPILOT_SMARTAP = 18,
1184 #[doc = "AirRails - <http://uaventure.com>"]
1185 MAV_AUTOPILOT_AIRRAILS = 19,
1186 #[doc = "Fusion Reflex - <https://fusion.engineering>"]
1187 MAV_AUTOPILOT_REFLEX = 20,
1188}
1189impl MavAutopilot {
1190 pub const DEFAULT: Self = Self::MAV_AUTOPILOT_GENERIC;
1191}
1192impl Default for MavAutopilot {
1193 fn default() -> Self {
1194 Self::DEFAULT
1195 }
1196}
1197#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1198#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1199#[cfg_attr(feature = "serde", serde(tag = "type"))]
1200#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1201#[repr(u32)]
1202#[doc = "Enumeration for battery charge states."]
1203pub enum MavBatteryChargeState {
1204 #[doc = "Low battery state is not provided"]
1205 MAV_BATTERY_CHARGE_STATE_UNDEFINED = 0,
1206 #[doc = "Battery is not in low state. Normal operation."]
1207 MAV_BATTERY_CHARGE_STATE_OK = 1,
1208 #[doc = "Battery state is low, warn and monitor close."]
1209 MAV_BATTERY_CHARGE_STATE_LOW = 2,
1210 #[doc = "Battery state is critical, return or abort immediately."]
1211 MAV_BATTERY_CHARGE_STATE_CRITICAL = 3,
1212 #[doc = "Battery state is too low for ordinary abort sequence. Perform fastest possible emergency stop to prevent damage."]
1213 MAV_BATTERY_CHARGE_STATE_EMERGENCY = 4,
1214 #[doc = "Battery failed, damage unavoidable. Possible causes (faults) are listed in MAV_BATTERY_FAULT."]
1215 MAV_BATTERY_CHARGE_STATE_FAILED = 5,
1216 #[doc = "Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in MAV_BATTERY_FAULT."]
1217 MAV_BATTERY_CHARGE_STATE_UNHEALTHY = 6,
1218 #[doc = "Battery is charging."]
1219 MAV_BATTERY_CHARGE_STATE_CHARGING = 7,
1220}
1221impl MavBatteryChargeState {
1222 pub const DEFAULT: Self = Self::MAV_BATTERY_CHARGE_STATE_UNDEFINED;
1223}
1224impl Default for MavBatteryChargeState {
1225 fn default() -> Self {
1226 Self::DEFAULT
1227 }
1228}
1229bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Smart battery supply status/fault flags (bitmask) for health indication. The battery must also report either MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY if any of these are set."] pub struct MavBatteryFault : u32 { # [doc = "Battery has deep discharged."] const MAV_BATTERY_FAULT_DEEP_DISCHARGE = 1 ; # [doc = "Voltage spikes."] const MAV_BATTERY_FAULT_SPIKES = 2 ; # [doc = "One or more cells have failed. Battery should also report MAV_BATTERY_CHARGE_STATE_FAILE (and should not be used)."] const MAV_BATTERY_FAULT_CELL_FAIL = 4 ; # [doc = "Over-current fault."] const MAV_BATTERY_FAULT_OVER_CURRENT = 8 ; # [doc = "Over-temperature fault."] const MAV_BATTERY_FAULT_OVER_TEMPERATURE = 16 ; # [doc = "Under-temperature fault."] const MAV_BATTERY_FAULT_UNDER_TEMPERATURE = 32 ; # [doc = "Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage)."] const MAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE = 64 ; # [doc = "Battery firmware is not compatible with current autopilot firmware."] const MAV_BATTERY_FAULT_INCOMPATIBLE_FIRMWARE = 128 ; # [doc = "Battery is not compatible due to cell configuration (e.g. 5s1p when vehicle requires 6s)."] const BATTERY_FAULT_INCOMPATIBLE_CELLS_CONFIGURATION = 256 ; } }
1230impl MavBatteryFault {
1231 pub const DEFAULT: Self = Self::MAV_BATTERY_FAULT_DEEP_DISCHARGE;
1232}
1233impl Default for MavBatteryFault {
1234 fn default() -> Self {
1235 Self::DEFAULT
1236 }
1237}
1238#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1239#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1240#[cfg_attr(feature = "serde", serde(tag = "type"))]
1241#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1242#[repr(u32)]
1243#[doc = "Enumeration of battery functions"]
1244pub enum MavBatteryFunction {
1245 #[doc = "Battery function is unknown"]
1246 MAV_BATTERY_FUNCTION_UNKNOWN = 0,
1247 #[doc = "Battery supports all flight systems"]
1248 MAV_BATTERY_FUNCTION_ALL = 1,
1249 #[doc = "Battery for the propulsion system"]
1250 MAV_BATTERY_FUNCTION_PROPULSION = 2,
1251 #[doc = "Avionics battery"]
1252 MAV_BATTERY_FUNCTION_AVIONICS = 3,
1253 #[doc = "Payload battery"]
1254 MAV_BATTERY_FUNCTION_PAYLOAD = 4,
1255}
1256impl MavBatteryFunction {
1257 pub const DEFAULT: Self = Self::MAV_BATTERY_FUNCTION_UNKNOWN;
1258}
1259impl Default for MavBatteryFunction {
1260 fn default() -> Self {
1261 Self::DEFAULT
1262 }
1263}
1264#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1265#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1266#[cfg_attr(feature = "serde", serde(tag = "type"))]
1267#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1268#[repr(u32)]
1269#[doc = "Battery mode. Note, the normal operation mode (i.e. when flying) should be reported as MAV_BATTERY_MODE_UNKNOWN to allow message trimming in normal flight."]
1270pub enum MavBatteryMode {
1271 #[doc = "Battery mode not supported/unknown battery mode/normal operation."]
1272 MAV_BATTERY_MODE_UNKNOWN = 0,
1273 #[doc = "Battery is auto discharging (towards storage level)."]
1274 MAV_BATTERY_MODE_AUTO_DISCHARGING = 1,
1275 #[doc = "Battery in hot-swap mode (current limited to prevent spikes that might damage sensitive electrical circuits)."]
1276 MAV_BATTERY_MODE_HOT_SWAP = 2,
1277}
1278impl MavBatteryMode {
1279 pub const DEFAULT: Self = Self::MAV_BATTERY_MODE_UNKNOWN;
1280}
1281impl Default for MavBatteryMode {
1282 fn default() -> Self {
1283 Self::DEFAULT
1284 }
1285}
1286#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1287#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1288#[cfg_attr(feature = "serde", serde(tag = "type"))]
1289#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1290#[repr(u32)]
1291#[doc = "Enumeration of battery types"]
1292pub enum MavBatteryType {
1293 #[doc = "Not specified."]
1294 MAV_BATTERY_TYPE_UNKNOWN = 0,
1295 #[doc = "Lithium polymer battery"]
1296 MAV_BATTERY_TYPE_LIPO = 1,
1297 #[doc = "Lithium-iron-phosphate battery"]
1298 MAV_BATTERY_TYPE_LIFE = 2,
1299 #[doc = "Lithium-ION battery"]
1300 MAV_BATTERY_TYPE_LION = 3,
1301 #[doc = "Nickel metal hydride battery"]
1302 MAV_BATTERY_TYPE_NIMH = 4,
1303}
1304impl MavBatteryType {
1305 pub const DEFAULT: Self = Self::MAV_BATTERY_TYPE_UNKNOWN;
1306}
1307impl Default for MavBatteryType {
1308 fn default() -> Self {
1309 Self::DEFAULT
1310 }
1311}
1312#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1313#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1314#[cfg_attr(feature = "serde", serde(tag = "type"))]
1315#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1316#[repr(u32)]
1317#[doc = "Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. NaN and INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current yaw or latitude rather than a specific value). See <https://mavlink.io/en/guide/xml_schema.html#MAV_CMD> for information about the structure of the MAV_CMD entries"]
1318pub enum MavCmd {
1319 #[doc = "Navigate to waypoint. This is intended for use in missions (for guided commands outside of missions use MAV_CMD_DO_REPOSITION)."]
1320 MAV_CMD_NAV_WAYPOINT = 16,
1321 #[doc = "Loiter around this waypoint an unlimited amount of time"]
1322 MAV_CMD_NAV_LOITER_UNLIM = 17,
1323 #[doc = "Loiter around this waypoint for X turns"]
1324 MAV_CMD_NAV_LOITER_TURNS = 18,
1325 #[doc = "Loiter at the specified latitude, longitude and altitude for a certain amount of time. Multicopter vehicles stop at the point (within a vehicle-specific acceptance radius). Forward-only moving vehicles (e.g. fixed-wing) circle the point with the specified radius/direction. If the Heading Required parameter (2) is non-zero forward moving aircraft will only leave the loiter circle once heading towards the next waypoint."]
1326 MAV_CMD_NAV_LOITER_TIME = 19,
1327 #[doc = "Return to launch location"]
1328 MAV_CMD_NAV_RETURN_TO_LAUNCH = 20,
1329 #[doc = "Land at location."]
1330 MAV_CMD_NAV_LAND = 21,
1331 #[doc = "Takeoff from ground / hand. Vehicles that support multiple takeoff modes (e.g. VTOL quadplane) should take off using the currently configured mode."]
1332 MAV_CMD_NAV_TAKEOFF = 22,
1333 #[doc = "Land at local position (local frame only)"]
1334 MAV_CMD_NAV_LAND_LOCAL = 23,
1335 #[doc = "Takeoff from local position (local frame only)"]
1336 MAV_CMD_NAV_TAKEOFF_LOCAL = 24,
1337 #[doc = "Vehicle following, i.e. this waypoint represents the position of a moving vehicle"]
1338 MAV_CMD_NAV_FOLLOW = 25,
1339 #[doc = "Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached."]
1340 MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT = 30,
1341 #[doc = "Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint."]
1342 MAV_CMD_NAV_LOITER_TO_ALT = 31,
1343 #[doc = "Begin following a target"]
1344 MAV_CMD_DO_FOLLOW = 32,
1345 #[doc = "Reposition the MAV after a follow target command has been sent"]
1346 MAV_CMD_DO_FOLLOW_REPOSITION = 33,
1347 #[doc = "Start orbiting on the circumference of a circle defined by the parameters. Setting values to NaN/INT32_MAX (as appropriate) results in using defaults."]
1348 MAV_CMD_DO_ORBIT = 34,
1349 #[doc = "Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras."]
1350 MAV_CMD_NAV_ROI = 80,
1351 #[doc = "Control autonomous path planning on the MAV."]
1352 MAV_CMD_NAV_PATHPLANNING = 81,
1353 #[doc = "Navigate to waypoint using a spline path."]
1354 MAV_CMD_NAV_SPLINE_WAYPOINT = 82,
1355 #[doc = "Takeoff from ground using VTOL mode, and transition to forward flight with specified heading. The command should be ignored by vehicles that dont support both VTOL and fixed-wing flight (multicopters, boats,etc.)."]
1356 MAV_CMD_NAV_VTOL_TAKEOFF = 84,
1357 #[doc = "Land using VTOL mode"]
1358 MAV_CMD_NAV_VTOL_LAND = 85,
1359 #[doc = "hand control over to an external controller"]
1360 MAV_CMD_NAV_GUIDED_ENABLE = 92,
1361 #[doc = "Delay the next navigation command a number of seconds or until a specified time"]
1362 MAV_CMD_NAV_DELAY = 93,
1363 #[doc = "Descend and place payload. Vehicle moves to specified location, descends until it detects a hanging payload has reached the ground, and then releases the payload. If ground is not detected before the reaching the maximum descent value (param1), the command will complete without releasing the payload."]
1364 MAV_CMD_NAV_PAYLOAD_PLACE = 94,
1365 #[doc = "NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration"]
1366 MAV_CMD_NAV_LAST = 95,
1367 #[doc = "Delay mission state machine."]
1368 MAV_CMD_CONDITION_DELAY = 112,
1369 #[doc = "Ascend/descend to target altitude at specified rate. Delay mission state machine until desired altitude reached."]
1370 MAV_CMD_CONDITION_CHANGE_ALT = 113,
1371 #[doc = "Delay mission state machine until within desired distance of next NAV point."]
1372 MAV_CMD_CONDITION_DISTANCE = 114,
1373 #[doc = "Reach a certain target angle."]
1374 MAV_CMD_CONDITION_YAW = 115,
1375 #[doc = "NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration"]
1376 MAV_CMD_CONDITION_LAST = 159,
1377 #[doc = "Set system mode."]
1378 MAV_CMD_DO_SET_MODE = 176,
1379 #[doc = "Jump to the desired command in the mission list. Repeat this action only the specified number of times"]
1380 MAV_CMD_DO_JUMP = 177,
1381 #[doc = "Change speed and/or throttle set points. The value persists until it is overridden or there is a mode change"]
1382 MAV_CMD_DO_CHANGE_SPEED = 178,
1383 #[doc = "Sets the home position to either to the current position or a specified position. The home position is the default position that the system will return to and land on. The position is set automatically by the system during the takeoff (and may also be set using this command). Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242)."]
1384 MAV_CMD_DO_SET_HOME = 179,
1385 #[doc = "Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter."]
1386 MAV_CMD_DO_SET_PARAMETER = 180,
1387 #[doc = "Set a relay to a condition."]
1388 MAV_CMD_DO_SET_RELAY = 181,
1389 #[doc = "Cycle a relay on and off for a desired number of cycles with a desired period."]
1390 MAV_CMD_DO_REPEAT_RELAY = 182,
1391 #[doc = "Set a servo to a desired PWM value."]
1392 MAV_CMD_DO_SET_SERVO = 183,
1393 #[doc = "Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period."]
1394 MAV_CMD_DO_REPEAT_SERVO = 184,
1395 #[doc = "0.5); the ACK should be either MAV_RESULT_FAILED or MAV_RESULT_UNSUPPORTED."]
1396 MAV_CMD_DO_FLIGHTTERMINATION = 185,
1397 #[doc = "Change altitude set point."]
1398 MAV_CMD_DO_CHANGE_ALTITUDE = 186,
1399 #[doc = "Sets actuators (e.g. servos) to a desired value. The actuator numbers are mapped to specific outputs (e.g. on any MAIN or AUX PWM or UAVCAN) using a flight-stack specific mechanism (i.e. a parameter)."]
1400 MAV_CMD_DO_SET_ACTUATOR = 187,
1401 #[doc = "Mission item to specify the start of a failsafe/landing return-path segment (the end of the segment is the next MAV_CMD_DO_LAND_START item). A vehicle that is using missions for landing (e.g. in a return mode) will join the mission on the closest path of the return-path segment (instead of MAV_CMD_DO_LAND_START or the nearest waypoint). The main use case is to minimize the failsafe flight path in corridor missions, where the inbound/outbound paths are constrained (by geofences) to the same particular path. The MAV_CMD_NAV_RETURN_PATH_START would be placed at the start of the return path. If a failsafe occurs on the outbound path the vehicle will move to the nearest point on the return path (which is parallel for this kind of mission), effectively turning round and following the shortest path to landing. If a failsafe occurs on the inbound path the vehicle is already on the return segment and will continue to landing. The Latitude/Longitude/Altitude are optional, and may be set to 0 if not needed. If specified, the item defines the waypoint at which the return segment starts. If sent using as a command, the vehicle will perform a mission landing (using the land segment if defined) or reject the command if mission landings are not supported, or no mission landing is defined. When used as a command any position information in the command is ignored."]
1402 MAV_CMD_DO_RETURN_PATH_START = 188,
1403 #[doc = "Mission item to mark the start of a mission landing pattern, or a command to land with a mission landing pattern. When used in a mission, this is a marker for the start of a sequence of mission items that represent a landing pattern. It should be followed by a navigation item that defines the first waypoint of the landing sequence. The start marker positional params are used only for selecting what landing pattern to use if several are defined in the mission (the selected pattern will be the one with the marker position that is closest to the vehicle when a landing is commanded). If the marker item position has zero-values for latitude, longitude, and altitude, then landing pattern selection is instead based on the position of the first waypoint in the landing sequence. \t When sent as a command it triggers a landing using a mission landing pattern. \t The location parameters are not used in this case, and should be set to 0."]
1404 MAV_CMD_DO_LAND_START = 189,
1405 #[doc = "Mission command to perform a landing from a rally point."]
1406 MAV_CMD_DO_RALLY_LAND = 190,
1407 #[doc = "Mission command to safely abort an autonomous landing."]
1408 MAV_CMD_DO_GO_AROUND = 191,
1409 #[doc = "Reposition the vehicle to a specific WGS84 global position. This command is intended for guided commands (for missions use MAV_CMD_NAV_WAYPOINT instead)."]
1410 MAV_CMD_DO_REPOSITION = 192,
1411 #[doc = "If in a GPS controlled position mode, hold the current position or continue."]
1412 MAV_CMD_DO_PAUSE_CONTINUE = 193,
1413 #[doc = "Set moving direction to forward or reverse."]
1414 MAV_CMD_DO_SET_REVERSE = 194,
1415 #[doc = "Sets the region of interest (ROI) to a location. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal is not to react to this message."]
1416 MAV_CMD_DO_SET_ROI_LOCATION = 195,
1417 #[doc = "Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message."]
1418 MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196,
1419 #[doc = "Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. After this command the gimbal manager should go back to manual input if available, and otherwise assume a neutral position."]
1420 MAV_CMD_DO_SET_ROI_NONE = 197,
1421 #[doc = "Mount tracks system with specified system ID. Determination of target vehicle position may be done with GLOBAL_POSITION_INT or any other means. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message."]
1422 MAV_CMD_DO_SET_ROI_SYSID = 198,
1423 #[doc = "Control onboard camera system."]
1424 MAV_CMD_DO_CONTROL_VIDEO = 200,
1425 #[doc = "Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras."]
1426 MAV_CMD_DO_SET_ROI = 201,
1427 #[doc = "Configure digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see <https://mavlink.io/en/services/camera_def.html> )."]
1428 MAV_CMD_DO_DIGICAM_CONFIGURE = 202,
1429 #[doc = "Control digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see <https://mavlink.io/en/services/camera_def.html> )."]
1430 MAV_CMD_DO_DIGICAM_CONTROL = 203,
1431 #[doc = "Mission command to configure a camera or antenna mount"]
1432 MAV_CMD_DO_MOUNT_CONFIGURE = 204,
1433 #[doc = "Mission command to control a camera or antenna mount"]
1434 MAV_CMD_DO_MOUNT_CONTROL = 205,
1435 #[doc = "Mission command to set camera trigger distance for this flight. The camera is triggered each time this distance is exceeded. This command can also be used to set the shutter integration time for the camera."]
1436 MAV_CMD_DO_SET_CAM_TRIGG_DIST = 206,
1437 #[doc = "Enable the geofence. This can be used in a mission or via the command protocol. The persistence/lifetime of the setting is undefined. Depending on flight stack implementation it may persist until superseded, or it may revert to a system default at the end of a mission. Flight stacks typically reset the setting to system defaults on reboot."]
1438 MAV_CMD_DO_FENCE_ENABLE = 207,
1439 #[doc = "Mission item/command to release a parachute or enable/disable auto release."]
1440 MAV_CMD_DO_PARACHUTE = 208,
1441 #[doc = "Command to perform motor test."]
1442 MAV_CMD_DO_MOTOR_TEST = 209,
1443 #[doc = "Change to/from inverted flight."]
1444 MAV_CMD_DO_INVERTED_FLIGHT = 210,
1445 #[doc = "Mission command to operate a gripper."]
1446 MAV_CMD_DO_GRIPPER = 211,
1447 #[doc = "Enable/disable autotune."]
1448 MAV_CMD_DO_AUTOTUNE_ENABLE = 212,
1449 #[doc = "Sets a desired vehicle turn angle and speed change."]
1450 MAV_CMD_NAV_SET_YAW_SPEED = 213,
1451 #[doc = "Mission command to set camera trigger interval for this flight. If triggering is enabled, the camera is triggered each time this interval expires. This command can also be used to set the shutter integration time for the camera."]
1452 MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL = 214,
1453 #[doc = "Mission command to control a camera or antenna mount, using a quaternion as reference."]
1454 MAV_CMD_DO_MOUNT_CONTROL_QUAT = 220,
1455 #[doc = "set id of master controller"]
1456 MAV_CMD_DO_GUIDED_MASTER = 221,
1457 #[doc = "Set limits for external control"]
1458 MAV_CMD_DO_GUIDED_LIMITS = 222,
1459 #[doc = "Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines"]
1460 MAV_CMD_DO_ENGINE_CONTROL = 223,
1461 #[doc = "Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed). If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items. \t Note that mission jump repeat counters are not reset unless param2 is set (see MAV_CMD_DO_JUMP param2). This command may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE. If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission. If the system is not in mission mode this command must not trigger a switch to mission mode. The mission may be \"reset\" using param2. Resetting sets jump counters to initial values (to reset counters without changing the current mission item set the param1 to `-1`). Resetting also explicitly changes a mission state of MISSION_STATE_COMPLETE to MISSION_STATE_PAUSED or MISSION_STATE_ACTIVE, potentially allowing it to resume when it is (next) in a mission mode. \t The command will ACK with MAV_RESULT_FAILED if the sequence number is out of range (including if there is no mission item)."]
1462 MAV_CMD_DO_SET_MISSION_CURRENT = 224,
1463 #[doc = "NOP - This command is only used to mark the upper limit of the DO commands in the enumeration"]
1464 MAV_CMD_DO_LAST = 240,
1465 #[doc = "Trigger calibration. This command will be only accepted if in pre-flight mode. Except for Temperature Calibration, only one sensor should be set in a single message and all others should be zero."]
1466 MAV_CMD_PREFLIGHT_CALIBRATION = 241,
1467 #[doc = "Set sensor offsets. This command will be only accepted if in pre-flight mode."]
1468 MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242,
1469 #[doc = "Trigger UAVCAN configuration (actuator ID assignment and direction mapping). Note that this maps to the legacy UAVCAN v0 function UAVCAN_ENUMERATE, which is intended to be executed just once during initial vehicle configuration (it is not a normal pre-flight command and has been poorly named)."]
1470 MAV_CMD_PREFLIGHT_UAVCAN = 243,
1471 #[doc = "Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode."]
1472 MAV_CMD_PREFLIGHT_STORAGE = 245,
1473 #[doc = "Request the reboot or shutdown of system components."]
1474 MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246,
1475 #[doc = "Override current mission with command to pause mission, pause mission and move to position, continue/resume mission. When param 1 indicates that the mission is paused (MAV_GOTO_DO_HOLD), param 2 defines whether it holds in place or moves to another position."]
1476 MAV_CMD_OVERRIDE_GOTO = 252,
1477 #[doc = "Mission command to set a Camera Auto Mount Pivoting Oblique Survey (Replaces CAM_TRIGG_DIST for this purpose). The camera is triggered each time this distance is exceeded, then the mount moves to the next position. Params 4~6 set-up the angle limits and number of positions for oblique survey, where mount-enabled vehicles automatically roll the camera between shots to emulate an oblique camera setup (providing an increased HFOV). This command can also be used to set the shutter integration time for the camera."]
1478 MAV_CMD_OBLIQUE_SURVEY = 260,
1479 #[doc = "Enable the specified standard MAVLink mode. If the specified mode is not supported, the vehicle should ACK with MAV_RESULT_FAILED. See <https://mavlink.io/en/services/standard_modes.html>"]
1480 MAV_CMD_DO_SET_STANDARD_MODE = 262,
1481 #[doc = "start running a mission"]
1482 MAV_CMD_MISSION_START = 300,
1483 #[doc = "Actuator testing command. This is similar to MAV_CMD_DO_MOTOR_TEST but operates on the level of output functions, i.e. it is possible to test Motor1 independent from which output it is configured on. Autopilots must NACK this command with MAV_RESULT_TEMPORARILY_REJECTED while armed."]
1484 MAV_CMD_ACTUATOR_TEST = 310,
1485 #[doc = "Actuator configuration command."]
1486 MAV_CMD_CONFIGURE_ACTUATOR = 311,
1487 #[doc = "Arms / Disarms a component"]
1488 MAV_CMD_COMPONENT_ARM_DISARM = 400,
1489 #[doc = "Instructs a target system to run pre-arm checks. This allows preflight checks to be run on demand, which may be useful on systems that normally run them at low rate, or which do not trigger checks when the armable state might have changed. This command should return MAV_RESULT_ACCEPTED if it will run the checks. The results of the checks are usually then reported in SYS_STATUS messages (this is system-specific). The command should return MAV_RESULT_TEMPORARILY_REJECTED if the system is already armed."]
1490 MAV_CMD_RUN_PREARM_CHECKS = 401,
1491 #[doc = "Turns illuminators ON/OFF. An illuminator is a light source that is used for lighting up dark areas external to the system: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light)."]
1492 MAV_CMD_ILLUMINATOR_ON_OFF = 405,
1493 #[doc = "Configures illuminator settings. An illuminator is a light source that is used for lighting up dark areas external to the system: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light)."]
1494 MAV_CMD_DO_ILLUMINATOR_CONFIGURE = 406,
1495 #[doc = "Request the home position from the vehicle. \t The vehicle will ACK the command and then emit the HOME_POSITION message."]
1496 MAV_CMD_GET_HOME_POSITION = 410,
1497 #[doc = "Inject artificial failure for testing purposes. Note that autopilots should implement an additional protection before accepting this command such as a specific param setting."]
1498 MAV_CMD_INJECT_FAILURE = 420,
1499 #[doc = "Starts receiver pairing."]
1500 MAV_CMD_START_RX_PAIR = 500,
1501 #[doc = "Request the interval between messages for a particular MAVLink message ID. The receiver should ACK the command and then emit its response in a MESSAGE_INTERVAL message."]
1502 MAV_CMD_GET_MESSAGE_INTERVAL = 510,
1503 #[doc = "Set the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM."]
1504 MAV_CMD_SET_MESSAGE_INTERVAL = 511,
1505 #[doc = "Request the target system(s) emit a single instance of a specified message (i.e. a \"one-shot\" version of MAV_CMD_SET_MESSAGE_INTERVAL)."]
1506 MAV_CMD_REQUEST_MESSAGE = 512,
1507 #[doc = "Request MAVLink protocol version compatibility. All receivers should ACK the command and then emit their capabilities in an PROTOCOL_VERSION message"]
1508 MAV_CMD_REQUEST_PROTOCOL_VERSION = 519,
1509 #[doc = "Request autopilot capabilities. The receiver should ACK the command and then emit its capabilities in an AUTOPILOT_VERSION message"]
1510 MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES = 520,
1511 #[doc = "Request camera information (CAMERA_INFORMATION)."]
1512 MAV_CMD_REQUEST_CAMERA_INFORMATION = 521,
1513 #[doc = "Request camera settings (CAMERA_SETTINGS)."]
1514 MAV_CMD_REQUEST_CAMERA_SETTINGS = 522,
1515 #[doc = "Request storage information (STORAGE_INFORMATION). Use the command's target_component to target a specific component's storage."]
1516 MAV_CMD_REQUEST_STORAGE_INFORMATION = 525,
1517 #[doc = "Format a storage medium. Once format is complete, a STORAGE_INFORMATION message is sent. Use the command's target_component to target a specific component's storage."]
1518 MAV_CMD_STORAGE_FORMAT = 526,
1519 #[doc = "Request camera capture status (CAMERA_CAPTURE_STATUS)"]
1520 MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS = 527,
1521 #[doc = "Request flight information (FLIGHT_INFORMATION)"]
1522 MAV_CMD_REQUEST_FLIGHT_INFORMATION = 528,
1523 #[doc = "Reset all camera settings to Factory Default"]
1524 MAV_CMD_RESET_CAMERA_SETTINGS = 529,
1525 #[doc = "Set camera running mode. Use NaN for reserved values. GCS will send a MAV_CMD_REQUEST_VIDEO_STREAM_STATUS command after a mode change if the camera supports video streaming."]
1526 MAV_CMD_SET_CAMERA_MODE = 530,
1527 #[doc = "Set camera zoom. Camera must respond with a CAMERA_SETTINGS message (on success)."]
1528 MAV_CMD_SET_CAMERA_ZOOM = 531,
1529 #[doc = "Set camera focus. Camera must respond with a CAMERA_SETTINGS message (on success)."]
1530 MAV_CMD_SET_CAMERA_FOCUS = 532,
1531 #[doc = "Set that a particular storage is the preferred location for saving photos, videos, and/or other media (e.g. to set that an SD card is used for storing videos). There can only be one preferred save location for each particular media type: setting a media usage flag will clear/reset that same flag if set on any other storage. If no flag is set the system should use its default storage. A target system can choose to always use default storage, in which case it should ACK the command with MAV_RESULT_UNSUPPORTED. A target system can choose to not allow a particular storage to be set as preferred storage, in which case it should ACK the command with MAV_RESULT_DENIED."]
1532 MAV_CMD_SET_STORAGE_USAGE = 533,
1533 #[doc = "Set camera source. Changes the camera's active sources on cameras with multiple image sensors."]
1534 MAV_CMD_SET_CAMERA_SOURCE = 534,
1535 #[doc = "Tagged jump target. Can be jumped to with MAV_CMD_DO_JUMP_TAG."]
1536 MAV_CMD_JUMP_TAG = 600,
1537 #[doc = "Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number."]
1538 MAV_CMD_DO_JUMP_TAG = 601,
1539 #[doc = "Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate."]
1540 MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000,
1541 #[doc = "Gimbal configuration to set which sysid/compid is in primary and secondary control."]
1542 MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001,
1543 #[doc = "Start image capture sequence. CAMERA_IMAGE_CAPTURED must be emitted after each capture. Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). It is also needed to specify the target camera in missions. When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero). If the param1 is 0 the autopilot should do both. When sent in a command the target MAVLink address is set using target_component. If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). If addressed to a MAVLink camera, param 1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels."]
1544 MAV_CMD_IMAGE_START_CAPTURE = 2000,
1545 #[doc = "Stop image capture sequence. Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). It is also needed to specify the target camera in missions. When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero). If the param1 is 0 the autopilot should do both. When sent in a command the target MAVLink address is set using target_component. If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). If addressed to a MAVLink camera, param1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels."]
1546 MAV_CMD_IMAGE_STOP_CAPTURE = 2001,
1547 #[doc = "Re-request a CAMERA_IMAGE_CAPTURED message."]
1548 MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE = 2002,
1549 #[doc = "Enable or disable on-board camera triggering system."]
1550 MAV_CMD_DO_TRIGGER_CONTROL = 2003,
1551 #[doc = "If the camera supports point visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_POINT is set), this command allows to initiate the tracking."]
1552 MAV_CMD_CAMERA_TRACK_POINT = 2004,
1553 #[doc = "If the camera supports rectangle visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE is set), this command allows to initiate the tracking."]
1554 MAV_CMD_CAMERA_TRACK_RECTANGLE = 2005,
1555 #[doc = "Stops ongoing tracking."]
1556 MAV_CMD_CAMERA_STOP_TRACKING = 2010,
1557 #[doc = "Starts video capture (recording)."]
1558 MAV_CMD_VIDEO_START_CAPTURE = 2500,
1559 #[doc = "Stop the current video capture (recording)."]
1560 MAV_CMD_VIDEO_STOP_CAPTURE = 2501,
1561 #[doc = "Start video streaming"]
1562 MAV_CMD_VIDEO_START_STREAMING = 2502,
1563 #[doc = "Stop the given video stream"]
1564 MAV_CMD_VIDEO_STOP_STREAMING = 2503,
1565 #[doc = "Request video stream information (VIDEO_STREAM_INFORMATION)"]
1566 MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION = 2504,
1567 #[doc = "Request video stream status (VIDEO_STREAM_STATUS)"]
1568 MAV_CMD_REQUEST_VIDEO_STREAM_STATUS = 2505,
1569 #[doc = "Request to start streaming logging data over MAVLink (see also LOGGING_DATA message)"]
1570 MAV_CMD_LOGGING_START = 2510,
1571 #[doc = "Request to stop streaming log data over MAVLink"]
1572 MAV_CMD_LOGGING_STOP = 2511,
1573 MAV_CMD_AIRFRAME_CONFIGURATION = 2520,
1574 #[doc = "Request to start/stop transmitting over the high latency telemetry"]
1575 MAV_CMD_CONTROL_HIGH_LATENCY = 2600,
1576 #[doc = "Create a panorama at the current position"]
1577 MAV_CMD_PANORAMA_CREATE = 2800,
1578 #[doc = "Request VTOL transition"]
1579 MAV_CMD_DO_VTOL_TRANSITION = 3000,
1580 #[doc = "Request authorization to arm the vehicle to a external entity, the arm authorizer is responsible to request all data that is needs from the vehicle before authorize or deny the request. \t\tIf approved the COMMAND_ACK message progress field should be set with period of time that this authorization is valid in seconds. \t\tIf the authorization is denied COMMAND_ACK.result_param2 should be set with one of the reasons in ARM_AUTH_DENIED_REASON."]
1581 MAV_CMD_ARM_AUTHORIZATION_REQUEST = 3001,
1582 #[doc = "This command sets the submode to standard guided when vehicle is in guided mode. The vehicle holds position and altitude and the user can input the desired velocities along all three axes."]
1583 MAV_CMD_SET_GUIDED_SUBMODE_STANDARD = 4000,
1584 #[doc = "This command sets submode circle when vehicle is in guided mode. Vehicle flies along a circle facing the center of the circle. The user can input the velocity along the circle and change the radius. If no input is given the vehicle will hold position."]
1585 MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE = 4001,
1586 #[doc = "Delay mission state machine until gate has been reached."]
1587 MAV_CMD_CONDITION_GATE = 4501,
1588 #[doc = "Fence return point (there can only be one such point in a geofence definition). If rally points are supported they should be used instead."]
1589 MAV_CMD_NAV_FENCE_RETURN_POINT = 5000,
1590 #[doc = "Fence vertex for an inclusion polygon (the polygon must not be self-intersecting). The vehicle must stay within this area. Minimum of 3 vertices required. The vertices for a polygon must be sent sequentially, each with param1 set to the total number of vertices in the polygon."]
1591 MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION = 5001,
1592 #[doc = "Fence vertex for an exclusion polygon (the polygon must not be self-intersecting). The vehicle must stay outside this area. Minimum of 3 vertices required. The vertices for a polygon must be sent sequentially, each with param1 set to the total number of vertices in the polygon."]
1593 MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION = 5002,
1594 #[doc = "Circular fence area. The vehicle must stay inside this area."]
1595 MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION = 5003,
1596 #[doc = "Circular fence area. The vehicle must stay outside this area."]
1597 MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION = 5004,
1598 #[doc = "Rally point. You can have multiple rally points defined."]
1599 MAV_CMD_NAV_RALLY_POINT = 5100,
1600 #[doc = "Commands the vehicle to respond with a sequence of messages UAVCAN_NODE_INFO, one message per every UAVCAN node that is online. Note that some of the response messages can be lost, which the receiver can detect easily by checking whether every received UAVCAN_NODE_STATUS has a matching message UAVCAN_NODE_INFO received earlier; if not, this command should be sent again in order to request re-transmission of the node information messages."]
1601 MAV_CMD_UAVCAN_GET_NODE_INFO = 5200,
1602 #[doc = "Change state of safety switch."]
1603 MAV_CMD_DO_SET_SAFETY_SWITCH_STATE = 5300,
1604 #[doc = "Trigger the start of an ADSB-out IDENT. This should only be used when requested to do so by an Air Traffic Controller in controlled airspace. This starts the IDENT which is then typically held for 18 seconds by the hardware per the Mode A, C, and S transponder spec."]
1605 MAV_CMD_DO_ADSB_OUT_IDENT = 10001,
1606 #[doc = "Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity."]
1607 MAV_CMD_PAYLOAD_PREPARE_DEPLOY = 30001,
1608 #[doc = "Control the payload deployment."]
1609 MAV_CMD_PAYLOAD_CONTROL_DEPLOY = 30002,
1610 #[doc = "Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location."]
1611 MAV_CMD_FIXED_MAG_CAL_YAW = 42006,
1612 #[doc = "Command to operate winch."]
1613 MAV_CMD_DO_WINCH = 42600,
1614 #[doc = "Provide an external position estimate for use when dead-reckoning. This is meant to be used for occasional position resets that may be provided by a external system such as a remote pilot using landmarks over a video link."]
1615 MAV_CMD_EXTERNAL_POSITION_ESTIMATE = 43003,
1616 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
1617 MAV_CMD_WAYPOINT_USER_1 = 31000,
1618 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
1619 MAV_CMD_WAYPOINT_USER_2 = 31001,
1620 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
1621 MAV_CMD_WAYPOINT_USER_3 = 31002,
1622 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
1623 MAV_CMD_WAYPOINT_USER_4 = 31003,
1624 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
1625 MAV_CMD_WAYPOINT_USER_5 = 31004,
1626 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
1627 MAV_CMD_SPATIAL_USER_1 = 31005,
1628 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
1629 MAV_CMD_SPATIAL_USER_2 = 31006,
1630 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
1631 MAV_CMD_SPATIAL_USER_3 = 31007,
1632 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
1633 MAV_CMD_SPATIAL_USER_4 = 31008,
1634 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
1635 MAV_CMD_SPATIAL_USER_5 = 31009,
1636 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
1637 MAV_CMD_USER_1 = 31010,
1638 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
1639 MAV_CMD_USER_2 = 31011,
1640 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
1641 MAV_CMD_USER_3 = 31012,
1642 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
1643 MAV_CMD_USER_4 = 31013,
1644 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
1645 MAV_CMD_USER_5 = 31014,
1646 #[doc = "Request forwarding of CAN packets from the given CAN bus to this component. CAN Frames are sent using CAN_FRAME and CANFD_FRAME messages"]
1647 MAV_CMD_CAN_FORWARD = 32000,
1648}
1649impl MavCmd {
1650 pub const DEFAULT: Self = Self::MAV_CMD_NAV_WAYPOINT;
1651}
1652impl Default for MavCmd {
1653 fn default() -> Self {
1654 Self::DEFAULT
1655 }
1656}
1657#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1658#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1659#[cfg_attr(feature = "serde", serde(tag = "type"))]
1660#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1661#[repr(u32)]
1662#[doc = "Possible actions an aircraft can take to avoid a collision."]
1663pub enum MavCollisionAction {
1664 #[doc = "Ignore any potential collisions"]
1665 MAV_COLLISION_ACTION_NONE = 0,
1666 #[doc = "Report potential collision"]
1667 MAV_COLLISION_ACTION_REPORT = 1,
1668 #[doc = "Ascend or Descend to avoid threat"]
1669 MAV_COLLISION_ACTION_ASCEND_OR_DESCEND = 2,
1670 #[doc = "Move horizontally to avoid threat"]
1671 MAV_COLLISION_ACTION_MOVE_HORIZONTALLY = 3,
1672 #[doc = "Aircraft to move perpendicular to the collision's velocity vector"]
1673 MAV_COLLISION_ACTION_MOVE_PERPENDICULAR = 4,
1674 #[doc = "Aircraft to fly directly back to its launch point"]
1675 MAV_COLLISION_ACTION_RTL = 5,
1676 #[doc = "Aircraft to stop in place"]
1677 MAV_COLLISION_ACTION_HOVER = 6,
1678}
1679impl MavCollisionAction {
1680 pub const DEFAULT: Self = Self::MAV_COLLISION_ACTION_NONE;
1681}
1682impl Default for MavCollisionAction {
1683 fn default() -> Self {
1684 Self::DEFAULT
1685 }
1686}
1687#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1688#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1689#[cfg_attr(feature = "serde", serde(tag = "type"))]
1690#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1691#[repr(u32)]
1692#[doc = "Source of information about this collision."]
1693pub enum MavCollisionSrc {
1694 #[doc = "ID field references ADSB_VEHICLE packets"]
1695 MAV_COLLISION_SRC_ADSB = 0,
1696 #[doc = "ID field references MAVLink SRC ID"]
1697 MAV_COLLISION_SRC_MAVLINK_GPS_GLOBAL_INT = 1,
1698}
1699impl MavCollisionSrc {
1700 pub const DEFAULT: Self = Self::MAV_COLLISION_SRC_ADSB;
1701}
1702impl Default for MavCollisionSrc {
1703 fn default() -> Self {
1704 Self::DEFAULT
1705 }
1706}
1707#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1708#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1709#[cfg_attr(feature = "serde", serde(tag = "type"))]
1710#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1711#[repr(u32)]
1712#[doc = "Aircraft-rated danger from this threat."]
1713pub enum MavCollisionThreatLevel {
1714 #[doc = "Not a threat"]
1715 MAV_COLLISION_THREAT_LEVEL_NONE = 0,
1716 #[doc = "Craft is mildly concerned about this threat"]
1717 MAV_COLLISION_THREAT_LEVEL_LOW = 1,
1718 #[doc = "Craft is panicking, and may take actions to avoid threat"]
1719 MAV_COLLISION_THREAT_LEVEL_HIGH = 2,
1720}
1721impl MavCollisionThreatLevel {
1722 pub const DEFAULT: Self = Self::MAV_COLLISION_THREAT_LEVEL_NONE;
1723}
1724impl Default for MavCollisionThreatLevel {
1725 fn default() -> Self {
1726 Self::DEFAULT
1727 }
1728}
1729#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1730#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1731#[cfg_attr(feature = "serde", serde(tag = "type"))]
1732#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1733#[repr(u32)]
1734#[doc = "Component ids (values) for the different types and instances of onboard hardware/software that might make up a MAVLink system (autopilot, cameras, servos, GPS systems, avoidance systems etc.). Components must use the appropriate ID in their source address when sending messages. Components can also use IDs to determine if they are the intended recipient of an incoming message. The MAV_COMP_ID_ALL value is used to indicate messages that must be processed by all components. When creating new entries, components that can have multiple instances (e.g. cameras, servos etc.) should be allocated sequential values. An appropriate number of values should be left free after these components to allow the number of instances to be expanded."]
1735pub enum MavComponent {
1736 #[doc = "Target id (target_component) used to broadcast messages to all components of the receiving system. Components should attempt to process messages with this component ID and forward to components on any other interfaces. Note: This is not a valid *source* component id for a message."]
1737 MAV_COMP_ID_ALL = 0,
1738 #[doc = "System flight controller component (\"autopilot\"). Only one autopilot is expected in a particular system."]
1739 MAV_COMP_ID_AUTOPILOT1 = 1,
1740 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1741 MAV_COMP_ID_USER1 = 25,
1742 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1743 MAV_COMP_ID_USER2 = 26,
1744 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1745 MAV_COMP_ID_USER3 = 27,
1746 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1747 MAV_COMP_ID_USER4 = 28,
1748 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1749 MAV_COMP_ID_USER5 = 29,
1750 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1751 MAV_COMP_ID_USER6 = 30,
1752 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1753 MAV_COMP_ID_USER7 = 31,
1754 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1755 MAV_COMP_ID_USER8 = 32,
1756 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1757 MAV_COMP_ID_USER9 = 33,
1758 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1759 MAV_COMP_ID_USER10 = 34,
1760 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1761 MAV_COMP_ID_USER11 = 35,
1762 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1763 MAV_COMP_ID_USER12 = 36,
1764 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1765 MAV_COMP_ID_USER13 = 37,
1766 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1767 MAV_COMP_ID_USER14 = 38,
1768 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1769 MAV_COMP_ID_USER15 = 39,
1770 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1771 MAV_COMP_ID_USER16 = 40,
1772 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1773 MAV_COMP_ID_USER17 = 41,
1774 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1775 MAV_COMP_ID_USER18 = 42,
1776 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1777 MAV_COMP_ID_USER19 = 43,
1778 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1779 MAV_COMP_ID_USER20 = 44,
1780 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1781 MAV_COMP_ID_USER21 = 45,
1782 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1783 MAV_COMP_ID_USER22 = 46,
1784 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1785 MAV_COMP_ID_USER23 = 47,
1786 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1787 MAV_COMP_ID_USER24 = 48,
1788 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1789 MAV_COMP_ID_USER25 = 49,
1790 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1791 MAV_COMP_ID_USER26 = 50,
1792 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1793 MAV_COMP_ID_USER27 = 51,
1794 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1795 MAV_COMP_ID_USER28 = 52,
1796 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1797 MAV_COMP_ID_USER29 = 53,
1798 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1799 MAV_COMP_ID_USER30 = 54,
1800 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1801 MAV_COMP_ID_USER31 = 55,
1802 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1803 MAV_COMP_ID_USER32 = 56,
1804 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1805 MAV_COMP_ID_USER33 = 57,
1806 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1807 MAV_COMP_ID_USER34 = 58,
1808 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1809 MAV_COMP_ID_USER35 = 59,
1810 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1811 MAV_COMP_ID_USER36 = 60,
1812 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1813 MAV_COMP_ID_USER37 = 61,
1814 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1815 MAV_COMP_ID_USER38 = 62,
1816 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1817 MAV_COMP_ID_USER39 = 63,
1818 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1819 MAV_COMP_ID_USER40 = 64,
1820 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1821 MAV_COMP_ID_USER41 = 65,
1822 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1823 MAV_COMP_ID_USER42 = 66,
1824 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1825 MAV_COMP_ID_USER43 = 67,
1826 #[doc = "Telemetry radio (e.g. SiK radio, or other component that emits RADIO_STATUS messages)."]
1827 MAV_COMP_ID_TELEMETRY_RADIO = 68,
1828 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1829 MAV_COMP_ID_USER45 = 69,
1830 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1831 MAV_COMP_ID_USER46 = 70,
1832 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1833 MAV_COMP_ID_USER47 = 71,
1834 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1835 MAV_COMP_ID_USER48 = 72,
1836 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1837 MAV_COMP_ID_USER49 = 73,
1838 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1839 MAV_COMP_ID_USER50 = 74,
1840 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1841 MAV_COMP_ID_USER51 = 75,
1842 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1843 MAV_COMP_ID_USER52 = 76,
1844 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1845 MAV_COMP_ID_USER53 = 77,
1846 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1847 MAV_COMP_ID_USER54 = 78,
1848 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1849 MAV_COMP_ID_USER55 = 79,
1850 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1851 MAV_COMP_ID_USER56 = 80,
1852 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1853 MAV_COMP_ID_USER57 = 81,
1854 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1855 MAV_COMP_ID_USER58 = 82,
1856 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1857 MAV_COMP_ID_USER59 = 83,
1858 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1859 MAV_COMP_ID_USER60 = 84,
1860 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1861 MAV_COMP_ID_USER61 = 85,
1862 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1863 MAV_COMP_ID_USER62 = 86,
1864 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1865 MAV_COMP_ID_USER63 = 87,
1866 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1867 MAV_COMP_ID_USER64 = 88,
1868 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1869 MAV_COMP_ID_USER65 = 89,
1870 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1871 MAV_COMP_ID_USER66 = 90,
1872 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1873 MAV_COMP_ID_USER67 = 91,
1874 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1875 MAV_COMP_ID_USER68 = 92,
1876 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1877 MAV_COMP_ID_USER69 = 93,
1878 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1879 MAV_COMP_ID_USER70 = 94,
1880 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1881 MAV_COMP_ID_USER71 = 95,
1882 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1883 MAV_COMP_ID_USER72 = 96,
1884 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1885 MAV_COMP_ID_USER73 = 97,
1886 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1887 MAV_COMP_ID_USER74 = 98,
1888 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1889 MAV_COMP_ID_USER75 = 99,
1890 #[doc = "Camera #1."]
1891 MAV_COMP_ID_CAMERA = 100,
1892 #[doc = "Camera #2."]
1893 MAV_COMP_ID_CAMERA2 = 101,
1894 #[doc = "Camera #3."]
1895 MAV_COMP_ID_CAMERA3 = 102,
1896 #[doc = "Camera #4."]
1897 MAV_COMP_ID_CAMERA4 = 103,
1898 #[doc = "Camera #5."]
1899 MAV_COMP_ID_CAMERA5 = 104,
1900 #[doc = "Camera #6."]
1901 MAV_COMP_ID_CAMERA6 = 105,
1902 #[doc = "Servo #1."]
1903 MAV_COMP_ID_SERVO1 = 140,
1904 #[doc = "Servo #2."]
1905 MAV_COMP_ID_SERVO2 = 141,
1906 #[doc = "Servo #3."]
1907 MAV_COMP_ID_SERVO3 = 142,
1908 #[doc = "Servo #4."]
1909 MAV_COMP_ID_SERVO4 = 143,
1910 #[doc = "Servo #5."]
1911 MAV_COMP_ID_SERVO5 = 144,
1912 #[doc = "Servo #6."]
1913 MAV_COMP_ID_SERVO6 = 145,
1914 #[doc = "Servo #7."]
1915 MAV_COMP_ID_SERVO7 = 146,
1916 #[doc = "Servo #8."]
1917 MAV_COMP_ID_SERVO8 = 147,
1918 #[doc = "Servo #9."]
1919 MAV_COMP_ID_SERVO9 = 148,
1920 #[doc = "Servo #10."]
1921 MAV_COMP_ID_SERVO10 = 149,
1922 #[doc = "Servo #11."]
1923 MAV_COMP_ID_SERVO11 = 150,
1924 #[doc = "Servo #12."]
1925 MAV_COMP_ID_SERVO12 = 151,
1926 #[doc = "Servo #13."]
1927 MAV_COMP_ID_SERVO13 = 152,
1928 #[doc = "Servo #14."]
1929 MAV_COMP_ID_SERVO14 = 153,
1930 #[doc = "Gimbal #1."]
1931 MAV_COMP_ID_GIMBAL = 154,
1932 #[doc = "Logging component."]
1933 MAV_COMP_ID_LOG = 155,
1934 #[doc = "Automatic Dependent Surveillance-Broadcast (ADS-B) component."]
1935 MAV_COMP_ID_ADSB = 156,
1936 #[doc = "On Screen Display (OSD) devices for video links."]
1937 MAV_COMP_ID_OSD = 157,
1938 #[doc = "Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter microservice."]
1939 MAV_COMP_ID_PERIPHERAL = 158,
1940 #[doc = "Gimbal ID for QX1."]
1941 MAV_COMP_ID_QX1_GIMBAL = 159,
1942 #[doc = "FLARM collision alert component."]
1943 MAV_COMP_ID_FLARM = 160,
1944 #[doc = "Parachute component."]
1945 MAV_COMP_ID_PARACHUTE = 161,
1946 #[doc = "Winch component."]
1947 MAV_COMP_ID_WINCH = 169,
1948 #[doc = "Gimbal #2."]
1949 MAV_COMP_ID_GIMBAL2 = 171,
1950 #[doc = "Gimbal #3."]
1951 MAV_COMP_ID_GIMBAL3 = 172,
1952 #[doc = "Gimbal #4"]
1953 MAV_COMP_ID_GIMBAL4 = 173,
1954 #[doc = "Gimbal #5."]
1955 MAV_COMP_ID_GIMBAL5 = 174,
1956 #[doc = "Gimbal #6."]
1957 MAV_COMP_ID_GIMBAL6 = 175,
1958 #[doc = "Battery #1."]
1959 MAV_COMP_ID_BATTERY = 180,
1960 #[doc = "Battery #2."]
1961 MAV_COMP_ID_BATTERY2 = 181,
1962 #[doc = "CAN over MAVLink client."]
1963 MAV_COMP_ID_MAVCAN = 189,
1964 #[doc = "Component that can generate/supply a mission flight plan (e.g. GCS or developer API)."]
1965 MAV_COMP_ID_MISSIONPLANNER = 190,
1966 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
1967 MAV_COMP_ID_ONBOARD_COMPUTER = 191,
1968 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
1969 MAV_COMP_ID_ONBOARD_COMPUTER2 = 192,
1970 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
1971 MAV_COMP_ID_ONBOARD_COMPUTER3 = 193,
1972 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
1973 MAV_COMP_ID_ONBOARD_COMPUTER4 = 194,
1974 #[doc = "Component that finds an optimal path between points based on a certain constraint (e.g. minimum snap, shortest path, cost, etc.)."]
1975 MAV_COMP_ID_PATHPLANNER = 195,
1976 #[doc = "Component that plans a collision free path between two points."]
1977 MAV_COMP_ID_OBSTACLE_AVOIDANCE = 196,
1978 #[doc = "Component that provides position estimates using VIO techniques."]
1979 MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY = 197,
1980 #[doc = "Component that manages pairing of vehicle and GCS."]
1981 MAV_COMP_ID_PAIRING_MANAGER = 198,
1982 #[doc = "Inertial Measurement Unit (IMU) #1."]
1983 MAV_COMP_ID_IMU = 200,
1984 #[doc = "Inertial Measurement Unit (IMU) #2."]
1985 MAV_COMP_ID_IMU_2 = 201,
1986 #[doc = "Inertial Measurement Unit (IMU) #3."]
1987 MAV_COMP_ID_IMU_3 = 202,
1988 #[doc = "GPS #1."]
1989 MAV_COMP_ID_GPS = 220,
1990 #[doc = "GPS #2."]
1991 MAV_COMP_ID_GPS2 = 221,
1992 #[doc = "Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)."]
1993 MAV_COMP_ID_ODID_TXRX_1 = 236,
1994 #[doc = "Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)."]
1995 MAV_COMP_ID_ODID_TXRX_2 = 237,
1996 #[doc = "Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)."]
1997 MAV_COMP_ID_ODID_TXRX_3 = 238,
1998 #[doc = "Component to bridge MAVLink to UDP (i.e. from a UART)."]
1999 MAV_COMP_ID_UDP_BRIDGE = 240,
2000 #[doc = "Component to bridge to UART (i.e. from UDP)."]
2001 MAV_COMP_ID_UART_BRIDGE = 241,
2002 #[doc = "Component handling TUNNEL messages (e.g. vendor specific GUI of a component)."]
2003 MAV_COMP_ID_TUNNEL_NODE = 242,
2004 #[doc = "Illuminator"]
2005 MAV_COMP_ID_ILLUMINATOR = 243,
2006 #[doc = "Deprecated, don't use. Component for handling system messages (e.g. to ARM, takeoff, etc.)."]
2007 MAV_COMP_ID_SYSTEM_CONTROL = 250,
2008}
2009impl MavComponent {
2010 pub const DEFAULT: Self = Self::MAV_COMP_ID_ALL;
2011}
2012impl Default for MavComponent {
2013 fn default() -> Self {
2014 Self::DEFAULT
2015 }
2016}
2017#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2018#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2019#[cfg_attr(feature = "serde", serde(tag = "type"))]
2020#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2021#[repr(u32)]
2022#[doc = "A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages."]
2023pub enum MavDataStream {
2024 #[doc = "Enable all data streams"]
2025 MAV_DATA_STREAM_ALL = 0,
2026 #[doc = "Enable IMU_RAW, GPS_RAW, GPS_STATUS packets."]
2027 MAV_DATA_STREAM_RAW_SENSORS = 1,
2028 #[doc = "Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS"]
2029 MAV_DATA_STREAM_EXTENDED_STATUS = 2,
2030 #[doc = "Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW"]
2031 MAV_DATA_STREAM_RC_CHANNELS = 3,
2032 #[doc = "Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT."]
2033 MAV_DATA_STREAM_RAW_CONTROLLER = 4,
2034 #[doc = "Enable LOCAL_POSITION, GLOBAL_POSITION_INT messages."]
2035 MAV_DATA_STREAM_POSITION = 6,
2036 #[doc = "Dependent on the autopilot"]
2037 MAV_DATA_STREAM_EXTRA1 = 10,
2038 #[doc = "Dependent on the autopilot"]
2039 MAV_DATA_STREAM_EXTRA2 = 11,
2040 #[doc = "Dependent on the autopilot"]
2041 MAV_DATA_STREAM_EXTRA3 = 12,
2042}
2043impl MavDataStream {
2044 pub const DEFAULT: Self = Self::MAV_DATA_STREAM_ALL;
2045}
2046impl Default for MavDataStream {
2047 fn default() -> Self {
2048 Self::DEFAULT
2049 }
2050}
2051#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2052#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2053#[cfg_attr(feature = "serde", serde(tag = "type"))]
2054#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2055#[repr(u32)]
2056#[doc = "Enumeration of distance sensor types"]
2057pub enum MavDistanceSensor {
2058 #[doc = "Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units"]
2059 MAV_DISTANCE_SENSOR_LASER = 0,
2060 #[doc = "Ultrasound rangefinder, e.g. MaxBotix units"]
2061 MAV_DISTANCE_SENSOR_ULTRASOUND = 1,
2062 #[doc = "Infrared rangefinder, e.g. Sharp units"]
2063 MAV_DISTANCE_SENSOR_INFRARED = 2,
2064 #[doc = "Radar type, e.g. uLanding units"]
2065 MAV_DISTANCE_SENSOR_RADAR = 3,
2066 #[doc = "Broken or unknown type, e.g. analog units"]
2067 MAV_DISTANCE_SENSOR_UNKNOWN = 4,
2068}
2069impl MavDistanceSensor {
2070 pub const DEFAULT: Self = Self::MAV_DISTANCE_SENSOR_LASER;
2071}
2072impl Default for MavDistanceSensor {
2073 fn default() -> Self {
2074 Self::DEFAULT
2075 }
2076}
2077#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2078#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2079#[cfg_attr(feature = "serde", serde(tag = "type"))]
2080#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2081#[repr(u32)]
2082#[doc = "Bitmap of options for the MAV_CMD_DO_REPOSITION"]
2083pub enum MavDoRepositionFlags {
2084 #[doc = "The aircraft should immediately transition into guided. This should not be set for follow me applications"]
2085 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE = 1,
2086}
2087impl MavDoRepositionFlags {
2088 pub const DEFAULT: Self = Self::MAV_DO_REPOSITION_FLAGS_CHANGE_MODE;
2089}
2090impl Default for MavDoRepositionFlags {
2091 fn default() -> Self {
2092 Self::DEFAULT
2093 }
2094}
2095#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2096#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2097#[cfg_attr(feature = "serde", serde(tag = "type"))]
2098#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2099#[repr(u32)]
2100#[doc = "Enumeration of estimator types"]
2101pub enum MavEstimatorType {
2102 #[doc = "Unknown type of the estimator."]
2103 MAV_ESTIMATOR_TYPE_UNKNOWN = 0,
2104 #[doc = "This is a naive estimator without any real covariance feedback."]
2105 MAV_ESTIMATOR_TYPE_NAIVE = 1,
2106 #[doc = "Computer vision based estimate. Might be up to scale."]
2107 MAV_ESTIMATOR_TYPE_VISION = 2,
2108 #[doc = "Visual-inertial estimate."]
2109 MAV_ESTIMATOR_TYPE_VIO = 3,
2110 #[doc = "Plain GPS estimate."]
2111 MAV_ESTIMATOR_TYPE_GPS = 4,
2112 #[doc = "Estimator integrating GPS and inertial sensing."]
2113 MAV_ESTIMATOR_TYPE_GPS_INS = 5,
2114 #[doc = "Estimate from external motion capturing system."]
2115 MAV_ESTIMATOR_TYPE_MOCAP = 6,
2116 #[doc = "Estimator based on lidar sensor input."]
2117 MAV_ESTIMATOR_TYPE_LIDAR = 7,
2118 #[doc = "Estimator on autopilot."]
2119 MAV_ESTIMATOR_TYPE_AUTOPILOT = 8,
2120}
2121impl MavEstimatorType {
2122 pub const DEFAULT: Self = Self::MAV_ESTIMATOR_TYPE_UNKNOWN;
2123}
2124impl Default for MavEstimatorType {
2125 fn default() -> Self {
2126 Self::DEFAULT
2127 }
2128}
2129#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2130#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2131#[cfg_attr(feature = "serde", serde(tag = "type"))]
2132#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2133#[repr(u32)]
2134#[doc = "Flags for CURRENT_EVENT_SEQUENCE."]
2135pub enum MavEventCurrentSequenceFlags {
2136 #[doc = "A sequence reset has happened (e.g. vehicle reboot)."]
2137 MAV_EVENT_CURRENT_SEQUENCE_FLAGS_RESET = 1,
2138}
2139impl MavEventCurrentSequenceFlags {
2140 pub const DEFAULT: Self = Self::MAV_EVENT_CURRENT_SEQUENCE_FLAGS_RESET;
2141}
2142impl Default for MavEventCurrentSequenceFlags {
2143 fn default() -> Self {
2144 Self::DEFAULT
2145 }
2146}
2147#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2148#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2149#[cfg_attr(feature = "serde", serde(tag = "type"))]
2150#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2151#[repr(u32)]
2152#[doc = "Reason for an event error response."]
2153pub enum MavEventErrorReason {
2154 #[doc = "The requested event is not available (anymore)."]
2155 MAV_EVENT_ERROR_REASON_UNAVAILABLE = 0,
2156}
2157impl MavEventErrorReason {
2158 pub const DEFAULT: Self = Self::MAV_EVENT_ERROR_REASON_UNAVAILABLE;
2159}
2160impl Default for MavEventErrorReason {
2161 fn default() -> Self {
2162 Self::DEFAULT
2163 }
2164}
2165#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2166#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2167#[cfg_attr(feature = "serde", serde(tag = "type"))]
2168#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2169#[repr(u32)]
2170#[doc = "Coordinate frames used by MAVLink. Not all frames are supported by all commands, messages, or vehicles. Global frames use the following naming conventions: - \"GLOBAL\": Global coordinate frame with WGS84 latitude/longitude and altitude positive over mean sea level (MSL) by default. The following modifiers may be used with \"GLOBAL\": - \"RELATIVE_ALT\": Altitude is relative to the vehicle home position rather than MSL. - \"TERRAIN_ALT\": Altitude is relative to ground level rather than MSL. - \"INT\": Latitude/longitude (in degrees) are scaled by multiplying by 1E7. Local frames use the following naming conventions: - \"LOCAL\": Origin of local frame is fixed relative to earth. Unless otherwise specified this origin is the origin of the vehicle position-estimator (\"EKF\"). - \"BODY\": Origin of local frame travels with the vehicle. NOTE, \"BODY\" does NOT indicate alignment of frame axis with vehicle attitude. - \"OFFSET\": Deprecated synonym for \"BODY\" (origin travels with the vehicle). Not to be used for new frames. Some deprecated frames do not follow these conventions (e.g. MAV_FRAME_BODY_NED and MAV_FRAME_BODY_OFFSET_NED)."]
2171pub enum MavFrame {
2172 #[doc = "Global (WGS84) coordinate frame + altitude relative to mean sea level (MSL)."]
2173 MAV_FRAME_GLOBAL = 0,
2174 #[doc = "NED local tangent frame (x: North, y: East, z: Down) with origin fixed relative to earth."]
2175 MAV_FRAME_LOCAL_NED = 1,
2176 #[doc = "NOT a coordinate frame, indicates a mission command."]
2177 MAV_FRAME_MISSION = 2,
2178 #[doc = "Global (WGS84) coordinate frame + altitude relative to the home position."]
2179 MAV_FRAME_GLOBAL_RELATIVE_ALT = 3,
2180 #[doc = "ENU local tangent frame (x: East, y: North, z: Up) with origin fixed relative to earth."]
2181 MAV_FRAME_LOCAL_ENU = 4,
2182 #[doc = "Global (WGS84) coordinate frame (scaled) + altitude relative to mean sea level (MSL)."]
2183 MAV_FRAME_GLOBAL_INT = 5,
2184 #[doc = "Global (WGS84) coordinate frame (scaled) + altitude relative to the home position."]
2185 MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6,
2186 #[doc = "NED local tangent frame (x: North, y: East, z: Down) with origin that travels with the vehicle."]
2187 MAV_FRAME_LOCAL_OFFSET_NED = 7,
2188 #[doc = "Same as MAV_FRAME_LOCAL_NED when used to represent position values. Same as MAV_FRAME_BODY_FRD when used with velocity/acceleration values."]
2189 MAV_FRAME_BODY_NED = 8,
2190 #[doc = "This is the same as MAV_FRAME_BODY_FRD."]
2191 MAV_FRAME_BODY_OFFSET_NED = 9,
2192 #[doc = "Global (WGS84) coordinate frame with AGL altitude (altitude at ground level)."]
2193 MAV_FRAME_GLOBAL_TERRAIN_ALT = 10,
2194 #[doc = "Global (WGS84) coordinate frame (scaled) with AGL altitude (altitude at ground level)."]
2195 MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11,
2196 #[doc = "FRD local frame aligned to the vehicle's attitude (x: Forward, y: Right, z: Down) with an origin that travels with vehicle."]
2197 MAV_FRAME_BODY_FRD = 12,
2198 #[doc = "MAV_FRAME_BODY_FLU - Body fixed frame of reference, Z-up (x: Forward, y: Left, z: Up)."]
2199 MAV_FRAME_RESERVED_13 = 13,
2200 #[doc = "MAV_FRAME_MOCAP_NED - Odometry local coordinate frame of data given by a motion capture system, Z-down (x: North, y: East, z: Down)."]
2201 MAV_FRAME_RESERVED_14 = 14,
2202 #[doc = "MAV_FRAME_MOCAP_ENU - Odometry local coordinate frame of data given by a motion capture system, Z-up (x: East, y: North, z: Up)."]
2203 MAV_FRAME_RESERVED_15 = 15,
2204 #[doc = "MAV_FRAME_VISION_NED - Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: North, y: East, z: Down)."]
2205 MAV_FRAME_RESERVED_16 = 16,
2206 #[doc = "MAV_FRAME_VISION_ENU - Odometry local coordinate frame of data given by a vision estimation system, Z-up (x: East, y: North, z: Up)."]
2207 MAV_FRAME_RESERVED_17 = 17,
2208 #[doc = "MAV_FRAME_ESTIM_NED - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: North, y: East, z: Down)."]
2209 MAV_FRAME_RESERVED_18 = 18,
2210 #[doc = "MAV_FRAME_ESTIM_ENU - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-up (x: East, y: North, z: Up)."]
2211 MAV_FRAME_RESERVED_19 = 19,
2212 #[doc = "FRD local tangent frame (x: Forward, y: Right, z: Down) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane."]
2213 MAV_FRAME_LOCAL_FRD = 20,
2214 #[doc = "FLU local tangent frame (x: Forward, y: Left, z: Up) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane."]
2215 MAV_FRAME_LOCAL_FLU = 21,
2216}
2217impl MavFrame {
2218 pub const DEFAULT: Self = Self::MAV_FRAME_GLOBAL;
2219}
2220impl Default for MavFrame {
2221 fn default() -> Self {
2222 Self::DEFAULT
2223 }
2224}
2225#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2226#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2227#[cfg_attr(feature = "serde", serde(tag = "type"))]
2228#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2229#[repr(u32)]
2230#[doc = "MAV FTP error codes (<https://mavlink.io/en/services/ftp.html>)"]
2231pub enum MavFtpErr {
2232 #[doc = "None: No error"]
2233 MAV_FTP_ERR_NONE = 0,
2234 #[doc = "Fail: Unknown failure"]
2235 MAV_FTP_ERR_FAIL = 1,
2236 #[doc = "FailErrno: Command failed, Err number sent back in PayloadHeader.data[1]. \t\tThis is a file-system error number understood by the server operating system."]
2237 MAV_FTP_ERR_FAILERRNO = 2,
2238 #[doc = "InvalidDataSize: Payload size is invalid"]
2239 MAV_FTP_ERR_INVALIDDATASIZE = 3,
2240 #[doc = "InvalidSession: Session is not currently open"]
2241 MAV_FTP_ERR_INVALIDSESSION = 4,
2242 #[doc = "NoSessionsAvailable: All available sessions are already in use"]
2243 MAV_FTP_ERR_NOSESSIONSAVAILABLE = 5,
2244 #[doc = "EOF: Offset past end of file for ListDirectory and ReadFile commands"]
2245 MAV_FTP_ERR_EOF = 6,
2246 #[doc = "UnknownCommand: Unknown command / opcode"]
2247 MAV_FTP_ERR_UNKNOWNCOMMAND = 7,
2248 #[doc = "FileExists: File/directory already exists"]
2249 MAV_FTP_ERR_FILEEXISTS = 8,
2250 #[doc = "FileProtected: File/directory is write protected"]
2251 MAV_FTP_ERR_FILEPROTECTED = 9,
2252 #[doc = "FileNotFound: File/directory not found"]
2253 MAV_FTP_ERR_FILENOTFOUND = 10,
2254}
2255impl MavFtpErr {
2256 pub const DEFAULT: Self = Self::MAV_FTP_ERR_NONE;
2257}
2258impl Default for MavFtpErr {
2259 fn default() -> Self {
2260 Self::DEFAULT
2261 }
2262}
2263#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2264#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2265#[cfg_attr(feature = "serde", serde(tag = "type"))]
2266#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2267#[repr(u32)]
2268#[doc = "MAV FTP opcodes: <https://mavlink.io/en/services/ftp.html>"]
2269pub enum MavFtpOpcode {
2270 #[doc = "None. Ignored, always ACKed"]
2271 MAV_FTP_OPCODE_NONE = 0,
2272 #[doc = "TerminateSession: Terminates open Read session"]
2273 MAV_FTP_OPCODE_TERMINATESESSION = 1,
2274 #[doc = "ResetSessions: Terminates all open read sessions"]
2275 MAV_FTP_OPCODE_RESETSESSION = 2,
2276 #[doc = "ListDirectory. List files and directories in path from offset"]
2277 MAV_FTP_OPCODE_LISTDIRECTORY = 3,
2278 #[doc = "OpenFileRO: Opens file at path for reading, returns session"]
2279 MAV_FTP_OPCODE_OPENFILERO = 4,
2280 #[doc = "ReadFile: Reads size bytes from offset in session"]
2281 MAV_FTP_OPCODE_READFILE = 5,
2282 #[doc = "CreateFile: Creates file at path for writing, returns session"]
2283 MAV_FTP_OPCODE_CREATEFILE = 6,
2284 #[doc = "WriteFile: Writes size bytes to offset in session"]
2285 MAV_FTP_OPCODE_WRITEFILE = 7,
2286 #[doc = "RemoveFile: Remove file at path"]
2287 MAV_FTP_OPCODE_REMOVEFILE = 8,
2288 #[doc = "CreateDirectory: Creates directory at path"]
2289 MAV_FTP_OPCODE_CREATEDIRECTORY = 9,
2290 #[doc = "RemoveDirectory: Removes directory at path. The directory must be empty."]
2291 MAV_FTP_OPCODE_REMOVEDIRECTORY = 10,
2292 #[doc = "OpenFileWO: Opens file at path for writing, returns session"]
2293 MAV_FTP_OPCODE_OPENFILEWO = 11,
2294 #[doc = "TruncateFile: Truncate file at path to offset length"]
2295 MAV_FTP_OPCODE_TRUNCATEFILE = 12,
2296 #[doc = "Rename: Rename path1 to path2"]
2297 MAV_FTP_OPCODE_RENAME = 13,
2298 #[doc = "CalcFileCRC32: Calculate CRC32 for file at path"]
2299 MAV_FTP_OPCODE_CALCFILECRC = 14,
2300 #[doc = "BurstReadFile: Burst download session file"]
2301 MAV_FTP_OPCODE_BURSTREADFILE = 15,
2302 #[doc = "ACK: ACK response"]
2303 MAV_FTP_OPCODE_ACK = 128,
2304 #[doc = "NAK: NAK response"]
2305 MAV_FTP_OPCODE_NAK = 129,
2306}
2307impl MavFtpOpcode {
2308 pub const DEFAULT: Self = Self::MAV_FTP_OPCODE_NONE;
2309}
2310impl Default for MavFtpOpcode {
2311 fn default() -> Self {
2312 Self::DEFAULT
2313 }
2314}
2315#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2316#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2317#[cfg_attr(feature = "serde", serde(tag = "type"))]
2318#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2319#[repr(u32)]
2320#[doc = "Fuel types for use in FUEL_TYPE. Fuel types specify the units for the maximum, available and consumed fuel, and for the flow rates."]
2321pub enum MavFuelType {
2322 #[doc = "Not specified. Fuel levels are normalized (i.e. maximum is 1, and other levels are relative to 1)."]
2323 MAV_FUEL_TYPE_UNKNOWN = 0,
2324 #[doc = "A generic liquid fuel. Fuel levels are in millilitres (ml). Fuel rates are in millilitres/second."]
2325 MAV_FUEL_TYPE_LIQUID = 1,
2326 #[doc = "A gas tank. Fuel levels are in kilo-Pascal (kPa), and flow rates are in milliliters per second (ml/s)."]
2327 MAV_FUEL_TYPE_GAS = 2,
2328}
2329impl MavFuelType {
2330 pub const DEFAULT: Self = Self::MAV_FUEL_TYPE_UNKNOWN;
2331}
2332impl Default for MavFuelType {
2333 fn default() -> Self {
2334 Self::DEFAULT
2335 }
2336}
2337bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to report status/failure cases for a power generator (used in GENERATOR_STATUS). Note that FAULTS are conditions that cause the generator to fail. Warnings are conditions that require attention before the next use (they indicate the system is not operating properly)."] pub struct MavGeneratorStatusFlag : u64 { # [doc = "Generator is off."] const MAV_GENERATOR_STATUS_FLAG_OFF = 1 ; # [doc = "Generator is ready to start generating power."] const MAV_GENERATOR_STATUS_FLAG_READY = 2 ; # [doc = "Generator is generating power."] const MAV_GENERATOR_STATUS_FLAG_GENERATING = 4 ; # [doc = "Generator is charging the batteries (generating enough power to charge and provide the load)."] const MAV_GENERATOR_STATUS_FLAG_CHARGING = 8 ; # [doc = "Generator is operating at a reduced maximum power."] const MAV_GENERATOR_STATUS_FLAG_REDUCED_POWER = 16 ; # [doc = "Generator is providing the maximum output."] const MAV_GENERATOR_STATUS_FLAG_MAXPOWER = 32 ; # [doc = "Generator is near the maximum operating temperature, cooling is insufficient."] const MAV_GENERATOR_STATUS_FLAG_OVERTEMP_WARNING = 64 ; # [doc = "Generator hit the maximum operating temperature and shutdown."] const MAV_GENERATOR_STATUS_FLAG_OVERTEMP_FAULT = 128 ; # [doc = "Power electronics are near the maximum operating temperature, cooling is insufficient."] const MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING = 256 ; # [doc = "Power electronics hit the maximum operating temperature and shutdown."] const MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT = 512 ; # [doc = "Power electronics experienced a fault and shutdown."] const MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_FAULT = 1024 ; # [doc = "The power source supplying the generator failed e.g. mechanical generator stopped, tether is no longer providing power, solar cell is in shade, hydrogen reaction no longer happening."] const MAV_GENERATOR_STATUS_FLAG_POWERSOURCE_FAULT = 2048 ; # [doc = "Generator controller having communication problems."] const MAV_GENERATOR_STATUS_FLAG_COMMUNICATION_WARNING = 4096 ; # [doc = "Power electronic or generator cooling system error."] const MAV_GENERATOR_STATUS_FLAG_COOLING_WARNING = 8192 ; # [doc = "Generator controller power rail experienced a fault."] const MAV_GENERATOR_STATUS_FLAG_POWER_RAIL_FAULT = 16384 ; # [doc = "Generator controller exceeded the overcurrent threshold and shutdown to prevent damage."] const MAV_GENERATOR_STATUS_FLAG_OVERCURRENT_FAULT = 32768 ; # [doc = "Generator controller detected a high current going into the batteries and shutdown to prevent battery damage."] const MAV_GENERATOR_STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT = 65536 ; # [doc = "Generator controller exceeded it's overvoltage threshold and shutdown to prevent it exceeding the voltage rating."] const MAV_GENERATOR_STATUS_FLAG_OVERVOLTAGE_FAULT = 131072 ; # [doc = "Batteries are under voltage (generator will not start)."] const MAV_GENERATOR_STATUS_FLAG_BATTERY_UNDERVOLT_FAULT = 262144 ; # [doc = "Generator start is inhibited by e.g. a safety switch."] const MAV_GENERATOR_STATUS_FLAG_START_INHIBITED = 524288 ; # [doc = "Generator requires maintenance."] const MAV_GENERATOR_STATUS_FLAG_MAINTENANCE_REQUIRED = 1048576 ; # [doc = "Generator is not ready to generate yet."] const MAV_GENERATOR_STATUS_FLAG_WARMING_UP = 2097152 ; # [doc = "Generator is idle."] const MAV_GENERATOR_STATUS_FLAG_IDLE = 4194304 ; } }
2338impl MavGeneratorStatusFlag {
2339 pub const DEFAULT: Self = Self::MAV_GENERATOR_STATUS_FLAG_OFF;
2340}
2341impl Default for MavGeneratorStatusFlag {
2342 fn default() -> Self {
2343 Self::DEFAULT
2344 }
2345}
2346#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2347#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2348#[cfg_attr(feature = "serde", serde(tag = "type"))]
2349#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2350#[repr(u32)]
2351#[doc = "Actions that may be specified in MAV_CMD_OVERRIDE_GOTO to override mission execution."]
2352pub enum MavGoto {
2353 #[doc = "Hold at the current position."]
2354 MAV_GOTO_DO_HOLD = 0,
2355 #[doc = "Continue with the next item in mission execution."]
2356 MAV_GOTO_DO_CONTINUE = 1,
2357 #[doc = "Hold at the current position of the system"]
2358 MAV_GOTO_HOLD_AT_CURRENT_POSITION = 2,
2359 #[doc = "Hold at the position specified in the parameters of the DO_HOLD action"]
2360 MAV_GOTO_HOLD_AT_SPECIFIED_POSITION = 3,
2361}
2362impl MavGoto {
2363 pub const DEFAULT: Self = Self::MAV_GOTO_DO_HOLD;
2364}
2365impl Default for MavGoto {
2366 fn default() -> Self {
2367 Self::DEFAULT
2368 }
2369}
2370#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2371#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2372#[cfg_attr(feature = "serde", serde(tag = "type"))]
2373#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2374#[repr(u32)]
2375#[doc = "Enumeration of landed detector states"]
2376pub enum MavLandedState {
2377 #[doc = "MAV landed state is unknown"]
2378 MAV_LANDED_STATE_UNDEFINED = 0,
2379 #[doc = "MAV is landed (on ground)"]
2380 MAV_LANDED_STATE_ON_GROUND = 1,
2381 #[doc = "MAV is in air"]
2382 MAV_LANDED_STATE_IN_AIR = 2,
2383 #[doc = "MAV currently taking off"]
2384 MAV_LANDED_STATE_TAKEOFF = 3,
2385 #[doc = "MAV currently landing"]
2386 MAV_LANDED_STATE_LANDING = 4,
2387}
2388impl MavLandedState {
2389 pub const DEFAULT: Self = Self::MAV_LANDED_STATE_UNDEFINED;
2390}
2391impl Default for MavLandedState {
2392 fn default() -> Self {
2393 Self::DEFAULT
2394 }
2395}
2396#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2397#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2398#[cfg_attr(feature = "serde", serde(tag = "type"))]
2399#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2400#[repr(u32)]
2401#[doc = "Result of mission operation (in a MISSION_ACK message)."]
2402pub enum MavMissionResult {
2403 #[doc = "mission accepted OK"]
2404 MAV_MISSION_ACCEPTED = 0,
2405 #[doc = "Generic error / not accepting mission commands at all right now."]
2406 MAV_MISSION_ERROR = 1,
2407 #[doc = "Coordinate frame is not supported."]
2408 MAV_MISSION_UNSUPPORTED_FRAME = 2,
2409 #[doc = "Command is not supported."]
2410 MAV_MISSION_UNSUPPORTED = 3,
2411 #[doc = "Mission items exceed storage space."]
2412 MAV_MISSION_NO_SPACE = 4,
2413 #[doc = "One of the parameters has an invalid value."]
2414 MAV_MISSION_INVALID = 5,
2415 #[doc = "param1 has an invalid value."]
2416 MAV_MISSION_INVALID_PARAM1 = 6,
2417 #[doc = "param2 has an invalid value."]
2418 MAV_MISSION_INVALID_PARAM2 = 7,
2419 #[doc = "param3 has an invalid value."]
2420 MAV_MISSION_INVALID_PARAM3 = 8,
2421 #[doc = "param4 has an invalid value."]
2422 MAV_MISSION_INVALID_PARAM4 = 9,
2423 #[doc = "x / param5 has an invalid value."]
2424 MAV_MISSION_INVALID_PARAM5_X = 10,
2425 #[doc = "y / param6 has an invalid value."]
2426 MAV_MISSION_INVALID_PARAM6_Y = 11,
2427 #[doc = "z / param7 has an invalid value."]
2428 MAV_MISSION_INVALID_PARAM7 = 12,
2429 #[doc = "Mission item received out of sequence"]
2430 MAV_MISSION_INVALID_SEQUENCE = 13,
2431 #[doc = "Not accepting any mission commands from this communication partner."]
2432 MAV_MISSION_DENIED = 14,
2433 #[doc = "Current mission operation cancelled (e.g. mission upload, mission download)."]
2434 MAV_MISSION_OPERATION_CANCELLED = 15,
2435}
2436impl MavMissionResult {
2437 pub const DEFAULT: Self = Self::MAV_MISSION_ACCEPTED;
2438}
2439impl Default for MavMissionResult {
2440 fn default() -> Self {
2441 Self::DEFAULT
2442 }
2443}
2444#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2445#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2446#[cfg_attr(feature = "serde", serde(tag = "type"))]
2447#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2448#[repr(u32)]
2449#[doc = "Type of mission items being requested/sent in mission protocol."]
2450pub enum MavMissionType {
2451 #[doc = "Items are mission commands for main mission."]
2452 MAV_MISSION_TYPE_MISSION = 0,
2453 #[doc = "Specifies GeoFence area(s). Items are MAV_CMD_NAV_FENCE_ GeoFence items."]
2454 MAV_MISSION_TYPE_FENCE = 1,
2455 #[doc = "Specifies the rally points for the vehicle. Rally points are alternative RTL points. Items are MAV_CMD_NAV_RALLY_POINT rally point items."]
2456 MAV_MISSION_TYPE_RALLY = 2,
2457 #[doc = "Only used in MISSION_CLEAR_ALL to clear all mission types."]
2458 MAV_MISSION_TYPE_ALL = 255,
2459}
2460impl MavMissionType {
2461 pub const DEFAULT: Self = Self::MAV_MISSION_TYPE_MISSION;
2462}
2463impl Default for MavMissionType {
2464 fn default() -> Self {
2465 Self::DEFAULT
2466 }
2467}
2468#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2469#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2470#[cfg_attr(feature = "serde", serde(tag = "type"))]
2471#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2472#[repr(u32)]
2473#[doc = "These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override."]
2474pub enum MavMode {
2475 #[doc = "System is not ready to fly, booting, calibrating, etc. No flag is set."]
2476 MAV_MODE_PREFLIGHT = 0,
2477 #[doc = "System is allowed to be active, under assisted RC control."]
2478 MAV_MODE_STABILIZE_DISARMED = 80,
2479 #[doc = "System is allowed to be active, under assisted RC control."]
2480 MAV_MODE_STABILIZE_ARMED = 208,
2481 #[doc = "System is allowed to be active, under manual (RC) control, no stabilization"]
2482 MAV_MODE_MANUAL_DISARMED = 64,
2483 #[doc = "System is allowed to be active, under manual (RC) control, no stabilization"]
2484 MAV_MODE_MANUAL_ARMED = 192,
2485 #[doc = "System is allowed to be active, under autonomous control, manual setpoint"]
2486 MAV_MODE_GUIDED_DISARMED = 88,
2487 #[doc = "System is allowed to be active, under autonomous control, manual setpoint"]
2488 MAV_MODE_GUIDED_ARMED = 216,
2489 #[doc = "System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)"]
2490 MAV_MODE_AUTO_DISARMED = 92,
2491 #[doc = "System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)"]
2492 MAV_MODE_AUTO_ARMED = 220,
2493 #[doc = "UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only."]
2494 MAV_MODE_TEST_DISARMED = 66,
2495 #[doc = "UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only."]
2496 MAV_MODE_TEST_ARMED = 194,
2497}
2498impl MavMode {
2499 pub const DEFAULT: Self = Self::MAV_MODE_PREFLIGHT;
2500}
2501impl Default for MavMode {
2502 fn default() -> Self {
2503 Self::DEFAULT
2504 }
2505}
2506bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These flags encode the MAV mode."] pub struct MavModeFlag : u8 { # [doc = "0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. Additional note: this flag is to be ignore when sent in the command MAV_CMD_DO_SET_MODE and MAV_CMD_COMPONENT_ARM_DISARM shall be used instead. The flag can still be used to report the armed state."] const MAV_MODE_FLAG_SAFETY_ARMED = 128 ; # [doc = "0b01000000 remote control input is enabled."] const MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64 ; # [doc = "0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational."] const MAV_MODE_FLAG_HIL_ENABLED = 32 ; # [doc = "0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around."] const MAV_MODE_FLAG_STABILIZE_ENABLED = 16 ; # [doc = "0b00001000 guided mode enabled, system flies waypoints / mission items."] const MAV_MODE_FLAG_GUIDED_ENABLED = 8 ; # [doc = "0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation."] const MAV_MODE_FLAG_AUTO_ENABLED = 4 ; # [doc = "0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations."] const MAV_MODE_FLAG_TEST_ENABLED = 2 ; # [doc = "0b00000001 Reserved for future use."] const MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1 ; } }
2507impl MavModeFlag {
2508 pub const DEFAULT: Self = Self::MAV_MODE_FLAG_SAFETY_ARMED;
2509}
2510impl Default for MavModeFlag {
2511 fn default() -> Self {
2512 Self::DEFAULT
2513 }
2514}
2515#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2516#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2517#[cfg_attr(feature = "serde", serde(tag = "type"))]
2518#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2519#[repr(u32)]
2520#[doc = "These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not."]
2521pub enum MavModeFlagDecodePosition {
2522 #[doc = "First bit: 10000000"]
2523 MAV_MODE_FLAG_DECODE_POSITION_SAFETY = 128,
2524 #[doc = "Second bit: 01000000"]
2525 MAV_MODE_FLAG_DECODE_POSITION_MANUAL = 64,
2526 #[doc = "Third bit: 00100000"]
2527 MAV_MODE_FLAG_DECODE_POSITION_HIL = 32,
2528 #[doc = "Fourth bit: 00010000"]
2529 MAV_MODE_FLAG_DECODE_POSITION_STABILIZE = 16,
2530 #[doc = "Fifth bit: 00001000"]
2531 MAV_MODE_FLAG_DECODE_POSITION_GUIDED = 8,
2532 #[doc = "Sixth bit: 00000100"]
2533 MAV_MODE_FLAG_DECODE_POSITION_AUTO = 4,
2534 #[doc = "Seventh bit: 00000010"]
2535 MAV_MODE_FLAG_DECODE_POSITION_TEST = 2,
2536 #[doc = "Eighth bit: 00000001"]
2537 MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE = 1,
2538}
2539impl MavModeFlagDecodePosition {
2540 pub const DEFAULT: Self = Self::MAV_MODE_FLAG_DECODE_POSITION_SAFETY;
2541}
2542impl Default for MavModeFlagDecodePosition {
2543 fn default() -> Self {
2544 Self::DEFAULT
2545 }
2546}
2547bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Mode properties."] pub struct MavModeProperty : u32 { # [doc = "If set, this mode is an advanced mode. For example a rate-controlled manual mode might be advanced, whereas a position-controlled manual mode is not. A GCS can optionally use this flag to configure the UI for its intended users."] const MAV_MODE_PROPERTY_ADVANCED = 1 ; # [doc = "If set, this mode should not be added to the list of selectable modes. The mode might still be selected by the FC directly (for example as part of a failsafe)."] const MAV_MODE_PROPERTY_NOT_USER_SELECTABLE = 2 ; # [doc = "If set, this mode is automatically controlled (it may use but does not require a manual controller). If unset the mode is a assumed to require user input (be a manual mode)."] const MAV_MODE_PROPERTY_AUTO_MODE = 4 ; } }
2548impl MavModeProperty {
2549 pub const DEFAULT: Self = Self::MAV_MODE_PROPERTY_ADVANCED;
2550}
2551impl Default for MavModeProperty {
2552 fn default() -> Self {
2553 Self::DEFAULT
2554 }
2555}
2556#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2557#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2558#[cfg_attr(feature = "serde", serde(tag = "type"))]
2559#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2560#[repr(u32)]
2561#[doc = "Enumeration of possible mount operation modes. This message is used by obsolete/deprecated gimbal messages."]
2562pub enum MavMountMode {
2563 #[doc = "Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization"]
2564 MAV_MOUNT_MODE_RETRACT = 0,
2565 #[doc = "Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory."]
2566 MAV_MOUNT_MODE_NEUTRAL = 1,
2567 #[doc = "Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization"]
2568 MAV_MOUNT_MODE_MAVLINK_TARGETING = 2,
2569 #[doc = "Load neutral position and start RC Roll,Pitch,Yaw control with stabilization"]
2570 MAV_MOUNT_MODE_RC_TARGETING = 3,
2571 #[doc = "Load neutral position and start to point to Lat,Lon,Alt"]
2572 MAV_MOUNT_MODE_GPS_POINT = 4,
2573 #[doc = "Gimbal tracks system with specified system ID"]
2574 MAV_MOUNT_MODE_SYSID_TARGET = 5,
2575 #[doc = "Gimbal tracks home position"]
2576 MAV_MOUNT_MODE_HOME_LOCATION = 6,
2577}
2578impl MavMountMode {
2579 pub const DEFAULT: Self = Self::MAV_MOUNT_MODE_RETRACT;
2580}
2581impl Default for MavMountMode {
2582 fn default() -> Self {
2583 Self::DEFAULT
2584 }
2585}
2586#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2587#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2588#[cfg_attr(feature = "serde", serde(tag = "type"))]
2589#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2590#[repr(u32)]
2591pub enum MavOdidArmStatus {
2592 #[doc = "Passing arming checks."]
2593 MAV_ODID_ARM_STATUS_GOOD_TO_ARM = 0,
2594 #[doc = "Generic arming failure, see error string for details."]
2595 MAV_ODID_ARM_STATUS_PRE_ARM_FAIL_GENERIC = 1,
2596}
2597impl MavOdidArmStatus {
2598 pub const DEFAULT: Self = Self::MAV_ODID_ARM_STATUS_GOOD_TO_ARM;
2599}
2600impl Default for MavOdidArmStatus {
2601 fn default() -> Self {
2602 Self::DEFAULT
2603 }
2604}
2605#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2606#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2607#[cfg_attr(feature = "serde", serde(tag = "type"))]
2608#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2609#[repr(u32)]
2610pub enum MavOdidAuthType {
2611 #[doc = "No authentication type is specified."]
2612 MAV_ODID_AUTH_TYPE_NONE = 0,
2613 #[doc = "Signature for the UAS (Unmanned Aircraft System) ID."]
2614 MAV_ODID_AUTH_TYPE_UAS_ID_SIGNATURE = 1,
2615 #[doc = "Signature for the Operator ID."]
2616 MAV_ODID_AUTH_TYPE_OPERATOR_ID_SIGNATURE = 2,
2617 #[doc = "Signature for the entire message set."]
2618 MAV_ODID_AUTH_TYPE_MESSAGE_SET_SIGNATURE = 3,
2619 #[doc = "Authentication is provided by Network Remote ID."]
2620 MAV_ODID_AUTH_TYPE_NETWORK_REMOTE_ID = 4,
2621 #[doc = "The exact authentication type is indicated by the first byte of authentication_data and these type values are managed by ICAO."]
2622 MAV_ODID_AUTH_TYPE_SPECIFIC_AUTHENTICATION = 5,
2623}
2624impl MavOdidAuthType {
2625 pub const DEFAULT: Self = Self::MAV_ODID_AUTH_TYPE_NONE;
2626}
2627impl Default for MavOdidAuthType {
2628 fn default() -> Self {
2629 Self::DEFAULT
2630 }
2631}
2632#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2633#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2634#[cfg_attr(feature = "serde", serde(tag = "type"))]
2635#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2636#[repr(u32)]
2637pub enum MavOdidCategoryEu {
2638 #[doc = "The category for the UA, according to the EU specification, is undeclared."]
2639 MAV_ODID_CATEGORY_EU_UNDECLARED = 0,
2640 #[doc = "The category for the UA, according to the EU specification, is the Open category."]
2641 MAV_ODID_CATEGORY_EU_OPEN = 1,
2642 #[doc = "The category for the UA, according to the EU specification, is the Specific category."]
2643 MAV_ODID_CATEGORY_EU_SPECIFIC = 2,
2644 #[doc = "The category for the UA, according to the EU specification, is the Certified category."]
2645 MAV_ODID_CATEGORY_EU_CERTIFIED = 3,
2646}
2647impl MavOdidCategoryEu {
2648 pub const DEFAULT: Self = Self::MAV_ODID_CATEGORY_EU_UNDECLARED;
2649}
2650impl Default for MavOdidCategoryEu {
2651 fn default() -> Self {
2652 Self::DEFAULT
2653 }
2654}
2655#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2656#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2657#[cfg_attr(feature = "serde", serde(tag = "type"))]
2658#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2659#[repr(u32)]
2660pub enum MavOdidClassEu {
2661 #[doc = "The class for the UA, according to the EU specification, is undeclared."]
2662 MAV_ODID_CLASS_EU_UNDECLARED = 0,
2663 #[doc = "The class for the UA, according to the EU specification, is Class 0."]
2664 MAV_ODID_CLASS_EU_CLASS_0 = 1,
2665 #[doc = "The class for the UA, according to the EU specification, is Class 1."]
2666 MAV_ODID_CLASS_EU_CLASS_1 = 2,
2667 #[doc = "The class for the UA, according to the EU specification, is Class 2."]
2668 MAV_ODID_CLASS_EU_CLASS_2 = 3,
2669 #[doc = "The class for the UA, according to the EU specification, is Class 3."]
2670 MAV_ODID_CLASS_EU_CLASS_3 = 4,
2671 #[doc = "The class for the UA, according to the EU specification, is Class 4."]
2672 MAV_ODID_CLASS_EU_CLASS_4 = 5,
2673 #[doc = "The class for the UA, according to the EU specification, is Class 5."]
2674 MAV_ODID_CLASS_EU_CLASS_5 = 6,
2675 #[doc = "The class for the UA, according to the EU specification, is Class 6."]
2676 MAV_ODID_CLASS_EU_CLASS_6 = 7,
2677}
2678impl MavOdidClassEu {
2679 pub const DEFAULT: Self = Self::MAV_ODID_CLASS_EU_UNDECLARED;
2680}
2681impl Default for MavOdidClassEu {
2682 fn default() -> Self {
2683 Self::DEFAULT
2684 }
2685}
2686#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2687#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2688#[cfg_attr(feature = "serde", serde(tag = "type"))]
2689#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2690#[repr(u32)]
2691pub enum MavOdidClassificationType {
2692 #[doc = "The classification type for the UA is undeclared."]
2693 MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED = 0,
2694 #[doc = "The classification type for the UA follows EU (European Union) specifications."]
2695 MAV_ODID_CLASSIFICATION_TYPE_EU = 1,
2696}
2697impl MavOdidClassificationType {
2698 pub const DEFAULT: Self = Self::MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED;
2699}
2700impl Default for MavOdidClassificationType {
2701 fn default() -> Self {
2702 Self::DEFAULT
2703 }
2704}
2705#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2706#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2707#[cfg_attr(feature = "serde", serde(tag = "type"))]
2708#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2709#[repr(u32)]
2710pub enum MavOdidDescType {
2711 #[doc = "Optional free-form text description of the purpose of the flight."]
2712 MAV_ODID_DESC_TYPE_TEXT = 0,
2713 #[doc = "Optional additional clarification when status == MAV_ODID_STATUS_EMERGENCY."]
2714 MAV_ODID_DESC_TYPE_EMERGENCY = 1,
2715 #[doc = "Optional additional clarification when status != MAV_ODID_STATUS_EMERGENCY."]
2716 MAV_ODID_DESC_TYPE_EXTENDED_STATUS = 2,
2717}
2718impl MavOdidDescType {
2719 pub const DEFAULT: Self = Self::MAV_ODID_DESC_TYPE_TEXT;
2720}
2721impl Default for MavOdidDescType {
2722 fn default() -> Self {
2723 Self::DEFAULT
2724 }
2725}
2726#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2727#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2728#[cfg_attr(feature = "serde", serde(tag = "type"))]
2729#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2730#[repr(u32)]
2731pub enum MavOdidHeightRef {
2732 #[doc = "The height field is relative to the take-off location."]
2733 MAV_ODID_HEIGHT_REF_OVER_TAKEOFF = 0,
2734 #[doc = "The height field is relative to ground."]
2735 MAV_ODID_HEIGHT_REF_OVER_GROUND = 1,
2736}
2737impl MavOdidHeightRef {
2738 pub const DEFAULT: Self = Self::MAV_ODID_HEIGHT_REF_OVER_TAKEOFF;
2739}
2740impl Default for MavOdidHeightRef {
2741 fn default() -> Self {
2742 Self::DEFAULT
2743 }
2744}
2745#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2746#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2747#[cfg_attr(feature = "serde", serde(tag = "type"))]
2748#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2749#[repr(u32)]
2750pub enum MavOdidHorAcc {
2751 #[doc = "The horizontal accuracy is unknown."]
2752 MAV_ODID_HOR_ACC_UNKNOWN = 0,
2753 #[doc = "The horizontal accuracy is smaller than 10 Nautical Miles. 18.52 km."]
2754 MAV_ODID_HOR_ACC_10NM = 1,
2755 #[doc = "The horizontal accuracy is smaller than 4 Nautical Miles. 7.408 km."]
2756 MAV_ODID_HOR_ACC_4NM = 2,
2757 #[doc = "The horizontal accuracy is smaller than 2 Nautical Miles. 3.704 km."]
2758 MAV_ODID_HOR_ACC_2NM = 3,
2759 #[doc = "The horizontal accuracy is smaller than 1 Nautical Miles. 1.852 km."]
2760 MAV_ODID_HOR_ACC_1NM = 4,
2761 #[doc = "The horizontal accuracy is smaller than 0.5 Nautical Miles. 926 m."]
2762 MAV_ODID_HOR_ACC_0_5NM = 5,
2763 #[doc = "The horizontal accuracy is smaller than 0.3 Nautical Miles. 555.6 m."]
2764 MAV_ODID_HOR_ACC_0_3NM = 6,
2765 #[doc = "The horizontal accuracy is smaller than 0.1 Nautical Miles. 185.2 m."]
2766 MAV_ODID_HOR_ACC_0_1NM = 7,
2767 #[doc = "The horizontal accuracy is smaller than 0.05 Nautical Miles. 92.6 m."]
2768 MAV_ODID_HOR_ACC_0_05NM = 8,
2769 #[doc = "The horizontal accuracy is smaller than 30 meter."]
2770 MAV_ODID_HOR_ACC_30_METER = 9,
2771 #[doc = "The horizontal accuracy is smaller than 10 meter."]
2772 MAV_ODID_HOR_ACC_10_METER = 10,
2773 #[doc = "The horizontal accuracy is smaller than 3 meter."]
2774 MAV_ODID_HOR_ACC_3_METER = 11,
2775 #[doc = "The horizontal accuracy is smaller than 1 meter."]
2776 MAV_ODID_HOR_ACC_1_METER = 12,
2777}
2778impl MavOdidHorAcc {
2779 pub const DEFAULT: Self = Self::MAV_ODID_HOR_ACC_UNKNOWN;
2780}
2781impl Default for MavOdidHorAcc {
2782 fn default() -> Self {
2783 Self::DEFAULT
2784 }
2785}
2786#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2787#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2788#[cfg_attr(feature = "serde", serde(tag = "type"))]
2789#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2790#[repr(u32)]
2791pub enum MavOdidIdType {
2792 #[doc = "No type defined."]
2793 MAV_ODID_ID_TYPE_NONE = 0,
2794 #[doc = "Manufacturer Serial Number (ANSI/CTA-2063 format)."]
2795 MAV_ODID_ID_TYPE_SERIAL_NUMBER = 1,
2796 #[doc = "CAA (Civil Aviation Authority) registered ID. Format: [ICAO Country Code].[CAA Assigned ID]."]
2797 MAV_ODID_ID_TYPE_CAA_REGISTRATION_ID = 2,
2798 #[doc = "UTM (Unmanned Traffic Management) assigned UUID (RFC4122)."]
2799 MAV_ODID_ID_TYPE_UTM_ASSIGNED_UUID = 3,
2800 #[doc = "A 20 byte ID for a specific flight/session. The exact ID type is indicated by the first byte of uas_id and these type values are managed by ICAO."]
2801 MAV_ODID_ID_TYPE_SPECIFIC_SESSION_ID = 4,
2802}
2803impl MavOdidIdType {
2804 pub const DEFAULT: Self = Self::MAV_ODID_ID_TYPE_NONE;
2805}
2806impl Default for MavOdidIdType {
2807 fn default() -> Self {
2808 Self::DEFAULT
2809 }
2810}
2811#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2812#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2813#[cfg_attr(feature = "serde", serde(tag = "type"))]
2814#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2815#[repr(u32)]
2816pub enum MavOdidOperatorIdType {
2817 #[doc = "CAA (Civil Aviation Authority) registered operator ID."]
2818 MAV_ODID_OPERATOR_ID_TYPE_CAA = 0,
2819}
2820impl MavOdidOperatorIdType {
2821 pub const DEFAULT: Self = Self::MAV_ODID_OPERATOR_ID_TYPE_CAA;
2822}
2823impl Default for MavOdidOperatorIdType {
2824 fn default() -> Self {
2825 Self::DEFAULT
2826 }
2827}
2828#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2829#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2830#[cfg_attr(feature = "serde", serde(tag = "type"))]
2831#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2832#[repr(u32)]
2833pub enum MavOdidOperatorLocationType {
2834 #[doc = "The location/altitude of the operator is the same as the take-off location."]
2835 MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF = 0,
2836 #[doc = "The location/altitude of the operator is dynamic. E.g. based on live GNSS data."]
2837 MAV_ODID_OPERATOR_LOCATION_TYPE_LIVE_GNSS = 1,
2838 #[doc = "The location/altitude of the operator are fixed values."]
2839 MAV_ODID_OPERATOR_LOCATION_TYPE_FIXED = 2,
2840}
2841impl MavOdidOperatorLocationType {
2842 pub const DEFAULT: Self = Self::MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF;
2843}
2844impl Default for MavOdidOperatorLocationType {
2845 fn default() -> Self {
2846 Self::DEFAULT
2847 }
2848}
2849#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2850#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2851#[cfg_attr(feature = "serde", serde(tag = "type"))]
2852#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2853#[repr(u32)]
2854pub enum MavOdidSpeedAcc {
2855 #[doc = "The speed accuracy is unknown."]
2856 MAV_ODID_SPEED_ACC_UNKNOWN = 0,
2857 #[doc = "The speed accuracy is smaller than 10 meters per second."]
2858 MAV_ODID_SPEED_ACC_10_METERS_PER_SECOND = 1,
2859 #[doc = "The speed accuracy is smaller than 3 meters per second."]
2860 MAV_ODID_SPEED_ACC_3_METERS_PER_SECOND = 2,
2861 #[doc = "The speed accuracy is smaller than 1 meters per second."]
2862 MAV_ODID_SPEED_ACC_1_METERS_PER_SECOND = 3,
2863 #[doc = "The speed accuracy is smaller than 0.3 meters per second."]
2864 MAV_ODID_SPEED_ACC_0_3_METERS_PER_SECOND = 4,
2865}
2866impl MavOdidSpeedAcc {
2867 pub const DEFAULT: Self = Self::MAV_ODID_SPEED_ACC_UNKNOWN;
2868}
2869impl Default for MavOdidSpeedAcc {
2870 fn default() -> Self {
2871 Self::DEFAULT
2872 }
2873}
2874#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2875#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2876#[cfg_attr(feature = "serde", serde(tag = "type"))]
2877#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2878#[repr(u32)]
2879pub enum MavOdidStatus {
2880 #[doc = "The status of the (UA) Unmanned Aircraft is undefined."]
2881 MAV_ODID_STATUS_UNDECLARED = 0,
2882 #[doc = "The UA is on the ground."]
2883 MAV_ODID_STATUS_GROUND = 1,
2884 #[doc = "The UA is in the air."]
2885 MAV_ODID_STATUS_AIRBORNE = 2,
2886 #[doc = "The UA is having an emergency."]
2887 MAV_ODID_STATUS_EMERGENCY = 3,
2888 #[doc = "The remote ID system is failing or unreliable in some way."]
2889 MAV_ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE = 4,
2890}
2891impl MavOdidStatus {
2892 pub const DEFAULT: Self = Self::MAV_ODID_STATUS_UNDECLARED;
2893}
2894impl Default for MavOdidStatus {
2895 fn default() -> Self {
2896 Self::DEFAULT
2897 }
2898}
2899#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2900#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2901#[cfg_attr(feature = "serde", serde(tag = "type"))]
2902#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2903#[repr(u32)]
2904pub enum MavOdidTimeAcc {
2905 #[doc = "The timestamp accuracy is unknown."]
2906 MAV_ODID_TIME_ACC_UNKNOWN = 0,
2907 #[doc = "The timestamp accuracy is smaller than or equal to 0.1 second."]
2908 MAV_ODID_TIME_ACC_0_1_SECOND = 1,
2909 #[doc = "The timestamp accuracy is smaller than or equal to 0.2 second."]
2910 MAV_ODID_TIME_ACC_0_2_SECOND = 2,
2911 #[doc = "The timestamp accuracy is smaller than or equal to 0.3 second."]
2912 MAV_ODID_TIME_ACC_0_3_SECOND = 3,
2913 #[doc = "The timestamp accuracy is smaller than or equal to 0.4 second."]
2914 MAV_ODID_TIME_ACC_0_4_SECOND = 4,
2915 #[doc = "The timestamp accuracy is smaller than or equal to 0.5 second."]
2916 MAV_ODID_TIME_ACC_0_5_SECOND = 5,
2917 #[doc = "The timestamp accuracy is smaller than or equal to 0.6 second."]
2918 MAV_ODID_TIME_ACC_0_6_SECOND = 6,
2919 #[doc = "The timestamp accuracy is smaller than or equal to 0.7 second."]
2920 MAV_ODID_TIME_ACC_0_7_SECOND = 7,
2921 #[doc = "The timestamp accuracy is smaller than or equal to 0.8 second."]
2922 MAV_ODID_TIME_ACC_0_8_SECOND = 8,
2923 #[doc = "The timestamp accuracy is smaller than or equal to 0.9 second."]
2924 MAV_ODID_TIME_ACC_0_9_SECOND = 9,
2925 #[doc = "The timestamp accuracy is smaller than or equal to 1.0 second."]
2926 MAV_ODID_TIME_ACC_1_0_SECOND = 10,
2927 #[doc = "The timestamp accuracy is smaller than or equal to 1.1 second."]
2928 MAV_ODID_TIME_ACC_1_1_SECOND = 11,
2929 #[doc = "The timestamp accuracy is smaller than or equal to 1.2 second."]
2930 MAV_ODID_TIME_ACC_1_2_SECOND = 12,
2931 #[doc = "The timestamp accuracy is smaller than or equal to 1.3 second."]
2932 MAV_ODID_TIME_ACC_1_3_SECOND = 13,
2933 #[doc = "The timestamp accuracy is smaller than or equal to 1.4 second."]
2934 MAV_ODID_TIME_ACC_1_4_SECOND = 14,
2935 #[doc = "The timestamp accuracy is smaller than or equal to 1.5 second."]
2936 MAV_ODID_TIME_ACC_1_5_SECOND = 15,
2937}
2938impl MavOdidTimeAcc {
2939 pub const DEFAULT: Self = Self::MAV_ODID_TIME_ACC_UNKNOWN;
2940}
2941impl Default for MavOdidTimeAcc {
2942 fn default() -> Self {
2943 Self::DEFAULT
2944 }
2945}
2946#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2947#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2948#[cfg_attr(feature = "serde", serde(tag = "type"))]
2949#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2950#[repr(u32)]
2951pub enum MavOdidUaType {
2952 #[doc = "No UA (Unmanned Aircraft) type defined."]
2953 MAV_ODID_UA_TYPE_NONE = 0,
2954 #[doc = "Aeroplane/Airplane. Fixed wing."]
2955 MAV_ODID_UA_TYPE_AEROPLANE = 1,
2956 #[doc = "Helicopter or multirotor."]
2957 MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR = 2,
2958 #[doc = "Gyroplane."]
2959 MAV_ODID_UA_TYPE_GYROPLANE = 3,
2960 #[doc = "VTOL (Vertical Take-Off and Landing). Fixed wing aircraft that can take off vertically."]
2961 MAV_ODID_UA_TYPE_HYBRID_LIFT = 4,
2962 #[doc = "Ornithopter."]
2963 MAV_ODID_UA_TYPE_ORNITHOPTER = 5,
2964 #[doc = "Glider."]
2965 MAV_ODID_UA_TYPE_GLIDER = 6,
2966 #[doc = "Kite."]
2967 MAV_ODID_UA_TYPE_KITE = 7,
2968 #[doc = "Free Balloon."]
2969 MAV_ODID_UA_TYPE_FREE_BALLOON = 8,
2970 #[doc = "Captive Balloon."]
2971 MAV_ODID_UA_TYPE_CAPTIVE_BALLOON = 9,
2972 #[doc = "Airship. E.g. a blimp."]
2973 MAV_ODID_UA_TYPE_AIRSHIP = 10,
2974 #[doc = "Free Fall/Parachute (unpowered)."]
2975 MAV_ODID_UA_TYPE_FREE_FALL_PARACHUTE = 11,
2976 #[doc = "Rocket."]
2977 MAV_ODID_UA_TYPE_ROCKET = 12,
2978 #[doc = "Tethered powered aircraft."]
2979 MAV_ODID_UA_TYPE_TETHERED_POWERED_AIRCRAFT = 13,
2980 #[doc = "Ground Obstacle."]
2981 MAV_ODID_UA_TYPE_GROUND_OBSTACLE = 14,
2982 #[doc = "Other type of aircraft not listed earlier."]
2983 MAV_ODID_UA_TYPE_OTHER = 15,
2984}
2985impl MavOdidUaType {
2986 pub const DEFAULT: Self = Self::MAV_ODID_UA_TYPE_NONE;
2987}
2988impl Default for MavOdidUaType {
2989 fn default() -> Self {
2990 Self::DEFAULT
2991 }
2992}
2993#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2994#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2995#[cfg_attr(feature = "serde", serde(tag = "type"))]
2996#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2997#[repr(u32)]
2998pub enum MavOdidVerAcc {
2999 #[doc = "The vertical accuracy is unknown."]
3000 MAV_ODID_VER_ACC_UNKNOWN = 0,
3001 #[doc = "The vertical accuracy is smaller than 150 meter."]
3002 MAV_ODID_VER_ACC_150_METER = 1,
3003 #[doc = "The vertical accuracy is smaller than 45 meter."]
3004 MAV_ODID_VER_ACC_45_METER = 2,
3005 #[doc = "The vertical accuracy is smaller than 25 meter."]
3006 MAV_ODID_VER_ACC_25_METER = 3,
3007 #[doc = "The vertical accuracy is smaller than 10 meter."]
3008 MAV_ODID_VER_ACC_10_METER = 4,
3009 #[doc = "The vertical accuracy is smaller than 3 meter."]
3010 MAV_ODID_VER_ACC_3_METER = 5,
3011 #[doc = "The vertical accuracy is smaller than 1 meter."]
3012 MAV_ODID_VER_ACC_1_METER = 6,
3013}
3014impl MavOdidVerAcc {
3015 pub const DEFAULT: Self = Self::MAV_ODID_VER_ACC_UNKNOWN;
3016}
3017impl Default for MavOdidVerAcc {
3018 fn default() -> Self {
3019 Self::DEFAULT
3020 }
3021}
3022#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3023#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3024#[cfg_attr(feature = "serde", serde(tag = "type"))]
3025#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3026#[repr(u32)]
3027#[doc = "Specifies the datatype of a MAVLink extended parameter."]
3028pub enum MavParamExtType {
3029 #[doc = "8-bit unsigned integer"]
3030 MAV_PARAM_EXT_TYPE_UINT8 = 1,
3031 #[doc = "8-bit signed integer"]
3032 MAV_PARAM_EXT_TYPE_INT8 = 2,
3033 #[doc = "16-bit unsigned integer"]
3034 MAV_PARAM_EXT_TYPE_UINT16 = 3,
3035 #[doc = "16-bit signed integer"]
3036 MAV_PARAM_EXT_TYPE_INT16 = 4,
3037 #[doc = "32-bit unsigned integer"]
3038 MAV_PARAM_EXT_TYPE_UINT32 = 5,
3039 #[doc = "32-bit signed integer"]
3040 MAV_PARAM_EXT_TYPE_INT32 = 6,
3041 #[doc = "64-bit unsigned integer"]
3042 MAV_PARAM_EXT_TYPE_UINT64 = 7,
3043 #[doc = "64-bit signed integer"]
3044 MAV_PARAM_EXT_TYPE_INT64 = 8,
3045 #[doc = "32-bit floating-point"]
3046 MAV_PARAM_EXT_TYPE_REAL32 = 9,
3047 #[doc = "64-bit floating-point"]
3048 MAV_PARAM_EXT_TYPE_REAL64 = 10,
3049 #[doc = "Custom Type"]
3050 MAV_PARAM_EXT_TYPE_CUSTOM = 11,
3051}
3052impl MavParamExtType {
3053 pub const DEFAULT: Self = Self::MAV_PARAM_EXT_TYPE_UINT8;
3054}
3055impl Default for MavParamExtType {
3056 fn default() -> Self {
3057 Self::DEFAULT
3058 }
3059}
3060#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3061#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3062#[cfg_attr(feature = "serde", serde(tag = "type"))]
3063#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3064#[repr(u32)]
3065#[doc = "Specifies the datatype of a MAVLink parameter."]
3066pub enum MavParamType {
3067 #[doc = "8-bit unsigned integer"]
3068 MAV_PARAM_TYPE_UINT8 = 1,
3069 #[doc = "8-bit signed integer"]
3070 MAV_PARAM_TYPE_INT8 = 2,
3071 #[doc = "16-bit unsigned integer"]
3072 MAV_PARAM_TYPE_UINT16 = 3,
3073 #[doc = "16-bit signed integer"]
3074 MAV_PARAM_TYPE_INT16 = 4,
3075 #[doc = "32-bit unsigned integer"]
3076 MAV_PARAM_TYPE_UINT32 = 5,
3077 #[doc = "32-bit signed integer"]
3078 MAV_PARAM_TYPE_INT32 = 6,
3079 #[doc = "64-bit unsigned integer"]
3080 MAV_PARAM_TYPE_UINT64 = 7,
3081 #[doc = "64-bit signed integer"]
3082 MAV_PARAM_TYPE_INT64 = 8,
3083 #[doc = "32-bit floating-point"]
3084 MAV_PARAM_TYPE_REAL32 = 9,
3085 #[doc = "64-bit floating-point"]
3086 MAV_PARAM_TYPE_REAL64 = 10,
3087}
3088impl MavParamType {
3089 pub const DEFAULT: Self = Self::MAV_PARAM_TYPE_UINT8;
3090}
3091impl Default for MavParamType {
3092 fn default() -> Self {
3093 Self::DEFAULT
3094 }
3095}
3096bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Power supply status flags (bitmask)"] pub struct MavPowerStatus : u16 { # [doc = "main brick power supply valid"] const MAV_POWER_STATUS_BRICK_VALID = 1 ; # [doc = "main servo power supply valid for FMU"] const MAV_POWER_STATUS_SERVO_VALID = 2 ; # [doc = "USB power is connected"] const MAV_POWER_STATUS_USB_CONNECTED = 4 ; # [doc = "peripheral supply is in over-current state"] const MAV_POWER_STATUS_PERIPH_OVERCURRENT = 8 ; # [doc = "hi-power peripheral supply is in over-current state"] const MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = 16 ; # [doc = "Power status has changed since boot"] const MAV_POWER_STATUS_CHANGED = 32 ; } }
3097impl MavPowerStatus {
3098 pub const DEFAULT: Self = Self::MAV_POWER_STATUS_BRICK_VALID;
3099}
3100impl Default for MavPowerStatus {
3101 fn default() -> Self {
3102 Self::DEFAULT
3103 }
3104}
3105bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability."] pub struct MavProtocolCapability : u64 { # [doc = "Autopilot supports the MISSION_ITEM float message type. Note that MISSION_ITEM is deprecated, and autopilots should use MISSION_INT instead."] const MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT = 1 ; # [doc = "Autopilot supports the new param float message type."] const MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT = 2 ; # [doc = "Autopilot supports MISSION_ITEM_INT scaled integer message type. Note that this flag must always be set if missions are supported, because missions must always use MISSION_ITEM_INT (rather than MISSION_ITEM, which is deprecated)."] const MAV_PROTOCOL_CAPABILITY_MISSION_INT = 4 ; # [doc = "Autopilot supports COMMAND_INT scaled integer message type."] const MAV_PROTOCOL_CAPABILITY_COMMAND_INT = 8 ; # [doc = "Parameter protocol uses byte-wise encoding of parameter values into param_value (float) fields: <https://mavlink.io/en/services/parameter.html#parameter-encoding>. Note that either this flag or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST should be set if the parameter protocol is supported."] const MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE = 16 ; # [doc = "Autopilot supports the File Transfer Protocol v1: <https://mavlink.io/en/services/ftp.html>."] const MAV_PROTOCOL_CAPABILITY_FTP = 32 ; # [doc = "Autopilot supports commanding attitude offboard."] const MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET = 64 ; # [doc = "Autopilot supports commanding position and velocity targets in local NED frame."] const MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED = 128 ; # [doc = "Autopilot supports commanding position and velocity targets in global scaled integers."] const MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT = 256 ; # [doc = "Autopilot supports terrain protocol / data handling."] const MAV_PROTOCOL_CAPABILITY_TERRAIN = 512 ; # [doc = "Reserved for future use."] const MAV_PROTOCOL_CAPABILITY_RESERVED3 = 1024 ; # [doc = "Autopilot supports the MAV_CMD_DO_FLIGHTTERMINATION command (flight termination)."] const MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION = 2048 ; # [doc = "Autopilot supports onboard compass calibration."] const MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION = 4096 ; # [doc = "Autopilot supports MAVLink version 2."] const MAV_PROTOCOL_CAPABILITY_MAVLINK2 = 8192 ; # [doc = "Autopilot supports mission fence protocol."] const MAV_PROTOCOL_CAPABILITY_MISSION_FENCE = 16384 ; # [doc = "Autopilot supports mission rally point protocol."] const MAV_PROTOCOL_CAPABILITY_MISSION_RALLY = 32768 ; # [doc = "Reserved for future use."] const MAV_PROTOCOL_CAPABILITY_RESERVED2 = 65536 ; # [doc = "Parameter protocol uses C-cast of parameter values to set the param_value (float) fields: <https://mavlink.io/en/services/parameter.html#parameter-encoding>. Note that either this flag or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE should be set if the parameter protocol is supported."] const MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST = 131072 ; # [doc = "This component implements/is a gimbal manager. This means the GIMBAL_MANAGER_INFORMATION, and other messages can be requested."] const MAV_PROTOCOL_CAPABILITY_COMPONENT_IMPLEMENTS_GIMBAL_MANAGER = 262144 ; # [doc = "Component supports locking control to a particular GCS independent of its system (via MAV_CMD_REQUEST_OPERATOR_CONTROL)."] const MAV_PROTOCOL_CAPABILITY_COMPONENT_ACCEPTS_GCS_CONTROL = 524288 ; } }
3106impl MavProtocolCapability {
3107 pub const DEFAULT: Self = Self::MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT;
3108}
3109impl Default for MavProtocolCapability {
3110 fn default() -> Self {
3111 Self::DEFAULT
3112 }
3113}
3114#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3115#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3116#[cfg_attr(feature = "serde", serde(tag = "type"))]
3117#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3118#[repr(u32)]
3119#[doc = "Result from a MAVLink command (MAV_CMD)"]
3120pub enum MavResult {
3121 #[doc = "Command is valid (is supported and has valid parameters), and was executed."]
3122 MAV_RESULT_ACCEPTED = 0,
3123 #[doc = "Command is valid, but cannot be executed at this time. This is used to indicate a problem that should be fixed just by waiting (e.g. a state machine is busy, can't arm because have not got GPS lock, etc.). Retrying later should work."]
3124 MAV_RESULT_TEMPORARILY_REJECTED = 1,
3125 #[doc = "Command is invalid (is supported but has invalid parameters). Retrying same command and parameters will not work."]
3126 MAV_RESULT_DENIED = 2,
3127 #[doc = "Command is not supported (unknown)."]
3128 MAV_RESULT_UNSUPPORTED = 3,
3129 #[doc = "Command is valid, but execution has failed. This is used to indicate any non-temporary or unexpected problem, i.e. any problem that must be fixed before the command can succeed/be retried. For example, attempting to write a file when out of memory, attempting to arm when sensors are not calibrated, etc."]
3130 MAV_RESULT_FAILED = 4,
3131 #[doc = "Command is valid and is being executed. This will be followed by further progress updates, i.e. the component may send further COMMAND_ACK messages with result MAV_RESULT_IN_PROGRESS (at a rate decided by the implementation), and must terminate by sending a COMMAND_ACK message with final result of the operation. The COMMAND_ACK.progress field can be used to indicate the progress of the operation."]
3132 MAV_RESULT_IN_PROGRESS = 5,
3133 #[doc = "Command has been cancelled (as a result of receiving a COMMAND_CANCEL message)."]
3134 MAV_RESULT_CANCELLED = 6,
3135 #[doc = "Command is only accepted when sent as a COMMAND_LONG."]
3136 MAV_RESULT_COMMAND_LONG_ONLY = 7,
3137 #[doc = "Command is only accepted when sent as a COMMAND_INT."]
3138 MAV_RESULT_COMMAND_INT_ONLY = 8,
3139 #[doc = "Command is invalid because a frame is required and the specified frame is not supported."]
3140 MAV_RESULT_COMMAND_UNSUPPORTED_MAV_FRAME = 9,
3141}
3142impl MavResult {
3143 pub const DEFAULT: Self = Self::MAV_RESULT_ACCEPTED;
3144}
3145impl Default for MavResult {
3146 fn default() -> Self {
3147 Self::DEFAULT
3148 }
3149}
3150#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3151#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3152#[cfg_attr(feature = "serde", serde(tag = "type"))]
3153#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3154#[repr(u32)]
3155#[doc = "The ROI (region of interest) for the vehicle. This can be be used by the vehicle for camera/vehicle attitude alignment (see MAV_CMD_NAV_ROI)."]
3156pub enum MavRoi {
3157 #[doc = "No region of interest."]
3158 MAV_ROI_NONE = 0,
3159 #[doc = "Point toward next waypoint, with optional pitch/roll/yaw offset."]
3160 MAV_ROI_WPNEXT = 1,
3161 #[doc = "Point toward given waypoint."]
3162 MAV_ROI_WPINDEX = 2,
3163 #[doc = "Point toward fixed location."]
3164 MAV_ROI_LOCATION = 3,
3165 #[doc = "Point toward of given id."]
3166 MAV_ROI_TARGET = 4,
3167}
3168impl MavRoi {
3169 pub const DEFAULT: Self = Self::MAV_ROI_NONE;
3170}
3171impl Default for MavRoi {
3172 fn default() -> Self {
3173 Self::DEFAULT
3174 }
3175}
3176#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3177#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3178#[cfg_attr(feature = "serde", serde(tag = "type"))]
3179#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3180#[repr(u32)]
3181#[doc = "Enumeration of sensor orientation, according to its rotations"]
3182pub enum MavSensorOrientation {
3183 #[doc = "Roll: 0, Pitch: 0, Yaw: 0"]
3184 MAV_SENSOR_ROTATION_NONE = 0,
3185 #[doc = "Roll: 0, Pitch: 0, Yaw: 45"]
3186 MAV_SENSOR_ROTATION_YAW_45 = 1,
3187 #[doc = "Roll: 0, Pitch: 0, Yaw: 90"]
3188 MAV_SENSOR_ROTATION_YAW_90 = 2,
3189 #[doc = "Roll: 0, Pitch: 0, Yaw: 135"]
3190 MAV_SENSOR_ROTATION_YAW_135 = 3,
3191 #[doc = "Roll: 0, Pitch: 0, Yaw: 180"]
3192 MAV_SENSOR_ROTATION_YAW_180 = 4,
3193 #[doc = "Roll: 0, Pitch: 0, Yaw: 225"]
3194 MAV_SENSOR_ROTATION_YAW_225 = 5,
3195 #[doc = "Roll: 0, Pitch: 0, Yaw: 270"]
3196 MAV_SENSOR_ROTATION_YAW_270 = 6,
3197 #[doc = "Roll: 0, Pitch: 0, Yaw: 315"]
3198 MAV_SENSOR_ROTATION_YAW_315 = 7,
3199 #[doc = "Roll: 180, Pitch: 0, Yaw: 0"]
3200 MAV_SENSOR_ROTATION_ROLL_180 = 8,
3201 #[doc = "Roll: 180, Pitch: 0, Yaw: 45"]
3202 MAV_SENSOR_ROTATION_ROLL_180_YAW_45 = 9,
3203 #[doc = "Roll: 180, Pitch: 0, Yaw: 90"]
3204 MAV_SENSOR_ROTATION_ROLL_180_YAW_90 = 10,
3205 #[doc = "Roll: 180, Pitch: 0, Yaw: 135"]
3206 MAV_SENSOR_ROTATION_ROLL_180_YAW_135 = 11,
3207 #[doc = "Roll: 0, Pitch: 180, Yaw: 0"]
3208 MAV_SENSOR_ROTATION_PITCH_180 = 12,
3209 #[doc = "Roll: 180, Pitch: 0, Yaw: 225"]
3210 MAV_SENSOR_ROTATION_ROLL_180_YAW_225 = 13,
3211 #[doc = "Roll: 180, Pitch: 0, Yaw: 270"]
3212 MAV_SENSOR_ROTATION_ROLL_180_YAW_270 = 14,
3213 #[doc = "Roll: 180, Pitch: 0, Yaw: 315"]
3214 MAV_SENSOR_ROTATION_ROLL_180_YAW_315 = 15,
3215 #[doc = "Roll: 90, Pitch: 0, Yaw: 0"]
3216 MAV_SENSOR_ROTATION_ROLL_90 = 16,
3217 #[doc = "Roll: 90, Pitch: 0, Yaw: 45"]
3218 MAV_SENSOR_ROTATION_ROLL_90_YAW_45 = 17,
3219 #[doc = "Roll: 90, Pitch: 0, Yaw: 90"]
3220 MAV_SENSOR_ROTATION_ROLL_90_YAW_90 = 18,
3221 #[doc = "Roll: 90, Pitch: 0, Yaw: 135"]
3222 MAV_SENSOR_ROTATION_ROLL_90_YAW_135 = 19,
3223 #[doc = "Roll: 270, Pitch: 0, Yaw: 0"]
3224 MAV_SENSOR_ROTATION_ROLL_270 = 20,
3225 #[doc = "Roll: 270, Pitch: 0, Yaw: 45"]
3226 MAV_SENSOR_ROTATION_ROLL_270_YAW_45 = 21,
3227 #[doc = "Roll: 270, Pitch: 0, Yaw: 90"]
3228 MAV_SENSOR_ROTATION_ROLL_270_YAW_90 = 22,
3229 #[doc = "Roll: 270, Pitch: 0, Yaw: 135"]
3230 MAV_SENSOR_ROTATION_ROLL_270_YAW_135 = 23,
3231 #[doc = "Roll: 0, Pitch: 90, Yaw: 0"]
3232 MAV_SENSOR_ROTATION_PITCH_90 = 24,
3233 #[doc = "Roll: 0, Pitch: 270, Yaw: 0"]
3234 MAV_SENSOR_ROTATION_PITCH_270 = 25,
3235 #[doc = "Roll: 0, Pitch: 180, Yaw: 90"]
3236 MAV_SENSOR_ROTATION_PITCH_180_YAW_90 = 26,
3237 #[doc = "Roll: 0, Pitch: 180, Yaw: 270"]
3238 MAV_SENSOR_ROTATION_PITCH_180_YAW_270 = 27,
3239 #[doc = "Roll: 90, Pitch: 90, Yaw: 0"]
3240 MAV_SENSOR_ROTATION_ROLL_90_PITCH_90 = 28,
3241 #[doc = "Roll: 180, Pitch: 90, Yaw: 0"]
3242 MAV_SENSOR_ROTATION_ROLL_180_PITCH_90 = 29,
3243 #[doc = "Roll: 270, Pitch: 90, Yaw: 0"]
3244 MAV_SENSOR_ROTATION_ROLL_270_PITCH_90 = 30,
3245 #[doc = "Roll: 90, Pitch: 180, Yaw: 0"]
3246 MAV_SENSOR_ROTATION_ROLL_90_PITCH_180 = 31,
3247 #[doc = "Roll: 270, Pitch: 180, Yaw: 0"]
3248 MAV_SENSOR_ROTATION_ROLL_270_PITCH_180 = 32,
3249 #[doc = "Roll: 90, Pitch: 270, Yaw: 0"]
3250 MAV_SENSOR_ROTATION_ROLL_90_PITCH_270 = 33,
3251 #[doc = "Roll: 180, Pitch: 270, Yaw: 0"]
3252 MAV_SENSOR_ROTATION_ROLL_180_PITCH_270 = 34,
3253 #[doc = "Roll: 270, Pitch: 270, Yaw: 0"]
3254 MAV_SENSOR_ROTATION_ROLL_270_PITCH_270 = 35,
3255 #[doc = "Roll: 90, Pitch: 180, Yaw: 90"]
3256 MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90 = 36,
3257 #[doc = "Roll: 90, Pitch: 0, Yaw: 270"]
3258 MAV_SENSOR_ROTATION_ROLL_90_YAW_270 = 37,
3259 #[doc = "Roll: 90, Pitch: 68, Yaw: 293"]
3260 MAV_SENSOR_ROTATION_ROLL_90_PITCH_68_YAW_293 = 38,
3261 #[doc = "Pitch: 315"]
3262 MAV_SENSOR_ROTATION_PITCH_315 = 39,
3263 #[doc = "Roll: 90, Pitch: 315"]
3264 MAV_SENSOR_ROTATION_ROLL_90_PITCH_315 = 40,
3265 #[doc = "Custom orientation"]
3266 MAV_SENSOR_ROTATION_CUSTOM = 100,
3267}
3268impl MavSensorOrientation {
3269 pub const DEFAULT: Self = Self::MAV_SENSOR_ROTATION_NONE;
3270}
3271impl Default for MavSensorOrientation {
3272 fn default() -> Self {
3273 Self::DEFAULT
3274 }
3275}
3276#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3277#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3278#[cfg_attr(feature = "serde", serde(tag = "type"))]
3279#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3280#[repr(u32)]
3281#[doc = "Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: <http://www.kiwisyslog.com/kb/info:-syslog-message-levels/>."]
3282pub enum MavSeverity {
3283 #[doc = "System is unusable. This is a \"panic\" condition."]
3284 MAV_SEVERITY_EMERGENCY = 0,
3285 #[doc = "Action should be taken immediately. Indicates error in non-critical systems."]
3286 MAV_SEVERITY_ALERT = 1,
3287 #[doc = "Action must be taken immediately. Indicates failure in a primary system."]
3288 MAV_SEVERITY_CRITICAL = 2,
3289 #[doc = "Indicates an error in secondary/redundant systems."]
3290 MAV_SEVERITY_ERROR = 3,
3291 #[doc = "Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning."]
3292 MAV_SEVERITY_WARNING = 4,
3293 #[doc = "An unusual event has occurred, though not an error condition. This should be investigated for the root cause."]
3294 MAV_SEVERITY_NOTICE = 5,
3295 #[doc = "Normal operational messages. Useful for logging. No action is required for these messages."]
3296 MAV_SEVERITY_INFO = 6,
3297 #[doc = "Useful non-operational messages that can assist in debugging. These should not occur during normal operation."]
3298 MAV_SEVERITY_DEBUG = 7,
3299}
3300impl MavSeverity {
3301 pub const DEFAULT: Self = Self::MAV_SEVERITY_EMERGENCY;
3302}
3303impl Default for MavSeverity {
3304 fn default() -> Self {
3305 Self::DEFAULT
3306 }
3307}
3308#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3309#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3310#[cfg_attr(feature = "serde", serde(tag = "type"))]
3311#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3312#[repr(u32)]
3313#[doc = "Standard modes with a well understood meaning across flight stacks and vehicle types. For example, most flight stack have the concept of a \"return\" or \"RTL\" mode that takes a vehicle to safety, even though the precise mechanics of this mode may differ. The modes supported by a flight stack can be queried using AVAILABLE_MODES and set using MAV_CMD_DO_SET_STANDARD_MODE. The current mode is streamed in CURRENT_MODE. See <https://mavlink.io/en/services/standard_modes.html>"]
3314pub enum MavStandardMode {
3315 #[doc = "Non standard mode. This may be used when reporting the mode if the current flight mode is not a standard mode."]
3316 MAV_STANDARD_MODE_NON_STANDARD = 0,
3317 #[doc = "Position mode (manual). Position-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold both position and altitude against wind and external forces. This mode can only be set by vehicles that can hold a fixed position. Multicopter (MC) vehicles actively brake and hold both position and altitude against wind and external forces. Hybrid MC/FW (\"VTOL\") vehicles first transition to multicopter mode (if needed) but otherwise behave in the same way as MC vehicles. Fixed-wing (FW) vehicles must not support this mode. Other vehicle types must not support this mode (this may be revisited through the PR process)."]
3318 MAV_STANDARD_MODE_POSITION_HOLD = 1,
3319 #[doc = "Orbit (manual). Position-controlled and stabilized manual mode. The vehicle circles around a fixed setpoint in the horizontal plane at a particular radius, altitude, and direction. Flight stacks may further allow manual control over the setpoint position, radius, direction, speed, and/or altitude of the circle, but this is not mandated. Flight stacks may support the [MAV_CMD_DO_ORBIT](<https://mavlink.io/en/messages/common.html#MAV_CMD_DO_ORBIT>) for changing the orbit parameters. MC and FW vehicles may support this mode. Hybrid MC/FW (\"VTOL\") vehicles may support this mode in MC/FW or both modes; if the mode is not supported by the current configuration the vehicle should transition to the supported configuration. Other vehicle types must not support this mode (this may be revisited through the PR process)."]
3320 MAV_STANDARD_MODE_ORBIT = 2,
3321 #[doc = "Cruise mode (manual). Position-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold their original track against wind and external forces. Fixed-wing (FW) vehicles level orientation and maintain current track and altitude against wind and external forces. Hybrid MC/FW (\"VTOL\") vehicles first transition to FW mode (if needed) but otherwise behave in the same way as MC vehicles. Multicopter (MC) vehicles must not support this mode. Other vehicle types must not support this mode (this may be revisited through the PR process)."]
3322 MAV_STANDARD_MODE_CRUISE = 3,
3323 #[doc = "Altitude hold (manual). Altitude-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold their altitude. MC vehicles continue with existing momentum and may move with wind (or other external forces). FW vehicles continue with current heading, but may be moved off-track by wind. Hybrid MC/FW (\"VTOL\") vehicles behave according to their current configuration/mode (FW or MC). Other vehicle types must not support this mode (this may be revisited through the PR process)."]
3324 MAV_STANDARD_MODE_ALTITUDE_HOLD = 4,
3325 #[doc = "Safe recovery mode (auto). Automatic mode that takes vehicle to a predefined safe location via a safe flight path, and may also automatically land the vehicle. This mode is more commonly referred to as RTL and/or or Smart RTL. The precise return location, flight path, and landing behaviour depend on vehicle configuration and type. For example, the vehicle might return to the home/launch location, a rally point, or the start of a mission landing, it might follow a direct path, mission path, or breadcrumb path, and land using a mission landing pattern or some other kind of descent."]
3326 MAV_STANDARD_MODE_SAFE_RECOVERY = 5,
3327 #[doc = "Mission mode (automatic). Automatic mode that executes MAVLink missions. Missions are executed from the current waypoint as soon as the mode is enabled."]
3328 MAV_STANDARD_MODE_MISSION = 6,
3329 #[doc = "Land mode (auto). Automatic mode that lands the vehicle at the current location. The precise landing behaviour depends on vehicle configuration and type."]
3330 MAV_STANDARD_MODE_LAND = 7,
3331 #[doc = "Takeoff mode (auto). Automatic takeoff mode. The precise takeoff behaviour depends on vehicle configuration and type."]
3332 MAV_STANDARD_MODE_TAKEOFF = 8,
3333}
3334impl MavStandardMode {
3335 pub const DEFAULT: Self = Self::MAV_STANDARD_MODE_NON_STANDARD;
3336}
3337impl Default for MavStandardMode {
3338 fn default() -> Self {
3339 Self::DEFAULT
3340 }
3341}
3342#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3343#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3344#[cfg_attr(feature = "serde", serde(tag = "type"))]
3345#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3346#[repr(u32)]
3347pub enum MavState {
3348 #[doc = "Uninitialized system, state is unknown."]
3349 MAV_STATE_UNINIT = 0,
3350 #[doc = "System is booting up."]
3351 MAV_STATE_BOOT = 1,
3352 #[doc = "System is calibrating and not flight-ready."]
3353 MAV_STATE_CALIBRATING = 2,
3354 #[doc = "System is grounded and on standby. It can be launched any time."]
3355 MAV_STATE_STANDBY = 3,
3356 #[doc = "System is active and might be already airborne. Motors are engaged."]
3357 MAV_STATE_ACTIVE = 4,
3358 #[doc = "System is in a non-normal flight mode (failsafe). It can however still navigate."]
3359 MAV_STATE_CRITICAL = 5,
3360 #[doc = "System is in a non-normal flight mode (failsafe). It lost control over parts or over the whole airframe. It is in mayday and going down."]
3361 MAV_STATE_EMERGENCY = 6,
3362 #[doc = "System just initialized its power-down sequence, will shut down now."]
3363 MAV_STATE_POWEROFF = 7,
3364 #[doc = "System is terminating itself (failsafe or commanded)."]
3365 MAV_STATE_FLIGHT_TERMINATION = 8,
3366}
3367impl MavState {
3368 pub const DEFAULT: Self = Self::MAV_STATE_UNINIT;
3369}
3370impl Default for MavState {
3371 fn default() -> Self {
3372 Self::DEFAULT
3373 }
3374}
3375bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These encode the sensors whose status is sent as part of the SYS_STATUS message."] pub struct MavSysStatusSensor : u32 { # [doc = "0x01 3D gyro"] const MAV_SYS_STATUS_SENSOR_3D_GYRO = 1 ; # [doc = "0x02 3D accelerometer"] const MAV_SYS_STATUS_SENSOR_3D_ACCEL = 2 ; # [doc = "0x04 3D magnetometer"] const MAV_SYS_STATUS_SENSOR_3D_MAG = 4 ; # [doc = "0x08 absolute pressure"] const MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE = 8 ; # [doc = "0x10 differential pressure"] const MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE = 16 ; # [doc = "0x20 GPS"] const MAV_SYS_STATUS_SENSOR_GPS = 32 ; # [doc = "0x40 optical flow"] const MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW = 64 ; # [doc = "0x80 computer vision position"] const MAV_SYS_STATUS_SENSOR_VISION_POSITION = 128 ; # [doc = "0x100 laser based position"] const MAV_SYS_STATUS_SENSOR_LASER_POSITION = 256 ; # [doc = "0x200 external ground truth (Vicon or Leica)"] const MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH = 512 ; # [doc = "0x400 3D angular rate control"] const MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL = 1024 ; # [doc = "0x800 attitude stabilization"] const MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = 2048 ; # [doc = "0x1000 yaw position"] const MAV_SYS_STATUS_SENSOR_YAW_POSITION = 4096 ; # [doc = "0x2000 z/altitude control"] const MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL = 8192 ; # [doc = "0x4000 x/y position control"] const MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL = 16384 ; # [doc = "0x8000 motor outputs / control"] const MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS = 32768 ; # [doc = "0x10000 RC receiver"] const MAV_SYS_STATUS_SENSOR_RC_RECEIVER = 65536 ; # [doc = "0x20000 2nd 3D gyro"] const MAV_SYS_STATUS_SENSOR_3D_GYRO2 = 131072 ; # [doc = "0x40000 2nd 3D accelerometer"] const MAV_SYS_STATUS_SENSOR_3D_ACCEL2 = 262144 ; # [doc = "0x80000 2nd 3D magnetometer"] const MAV_SYS_STATUS_SENSOR_3D_MAG2 = 524288 ; # [doc = "0x100000 geofence"] const MAV_SYS_STATUS_GEOFENCE = 1048576 ; # [doc = "0x200000 AHRS subsystem health"] const MAV_SYS_STATUS_AHRS = 2097152 ; # [doc = "0x400000 Terrain subsystem health"] const MAV_SYS_STATUS_TERRAIN = 4194304 ; # [doc = "0x800000 Motors are reversed"] const MAV_SYS_STATUS_REVERSE_MOTOR = 8388608 ; # [doc = "0x1000000 Logging"] const MAV_SYS_STATUS_LOGGING = 16777216 ; # [doc = "0x2000000 Battery"] const MAV_SYS_STATUS_SENSOR_BATTERY = 33554432 ; # [doc = "0x4000000 Proximity"] const MAV_SYS_STATUS_SENSOR_PROXIMITY = 67108864 ; # [doc = "0x8000000 Satellite Communication"] const MAV_SYS_STATUS_SENSOR_SATCOM = 134217728 ; # [doc = "0x10000000 pre-arm check status. Always healthy when armed"] const MAV_SYS_STATUS_PREARM_CHECK = 268435456 ; # [doc = "0x20000000 Avoidance/collision prevention"] const MAV_SYS_STATUS_OBSTACLE_AVOIDANCE = 536870912 ; # [doc = "0x40000000 propulsion (actuator, esc, motor or propellor)"] const MAV_SYS_STATUS_SENSOR_PROPULSION = 1073741824 ; # [doc = "0x80000000 Extended bit-field are used for further sensor status bits (needs to be set in onboard_control_sensors_present only)"] const MAV_SYS_STATUS_EXTENSION_USED = 2147483648 ; } }
3376impl MavSysStatusSensor {
3377 pub const DEFAULT: Self = Self::MAV_SYS_STATUS_SENSOR_3D_GYRO;
3378}
3379impl Default for MavSysStatusSensor {
3380 fn default() -> Self {
3381 Self::DEFAULT
3382 }
3383}
3384bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These encode the sensors whose status is sent as part of the SYS_STATUS message in the extended fields."] pub struct MavSysStatusSensorExtended : u32 { # [doc = "0x01 Recovery system (parachute, balloon, retracts etc)"] const MAV_SYS_STATUS_RECOVERY_SYSTEM = 1 ; } }
3385impl MavSysStatusSensorExtended {
3386 pub const DEFAULT: Self = Self::MAV_SYS_STATUS_RECOVERY_SYSTEM;
3387}
3388impl Default for MavSysStatusSensorExtended {
3389 fn default() -> Self {
3390 Self::DEFAULT
3391 }
3392}
3393#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3394#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3395#[cfg_attr(feature = "serde", serde(tag = "type"))]
3396#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3397#[repr(u32)]
3398pub enum MavTunnelPayloadType {
3399 #[doc = "Encoding of payload unknown."]
3400 MAV_TUNNEL_PAYLOAD_TYPE_UNKNOWN = 0,
3401 #[doc = "Registered for STorM32 gimbal controller."]
3402 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED0 = 200,
3403 #[doc = "Registered for STorM32 gimbal controller."]
3404 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED1 = 201,
3405 #[doc = "Registered for STorM32 gimbal controller."]
3406 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED2 = 202,
3407 #[doc = "Registered for STorM32 gimbal controller."]
3408 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED3 = 203,
3409 #[doc = "Registered for STorM32 gimbal controller."]
3410 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED4 = 204,
3411 #[doc = "Registered for STorM32 gimbal controller."]
3412 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED5 = 205,
3413 #[doc = "Registered for STorM32 gimbal controller."]
3414 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED6 = 206,
3415 #[doc = "Registered for STorM32 gimbal controller."]
3416 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED7 = 207,
3417 #[doc = "Registered for STorM32 gimbal controller."]
3418 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED8 = 208,
3419 #[doc = "Registered for STorM32 gimbal controller."]
3420 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED9 = 209,
3421 #[doc = "Registered for ModalAI remote OSD protocol."]
3422 MAV_TUNNEL_PAYLOAD_TYPE_MODALAI_REMOTE_OSD = 210,
3423 #[doc = "Registered for ModalAI ESC UART passthru protocol."]
3424 MAV_TUNNEL_PAYLOAD_TYPE_MODALAI_ESC_UART_PASSTHRU = 211,
3425 #[doc = "Registered for ModalAI vendor use."]
3426 MAV_TUNNEL_PAYLOAD_TYPE_MODALAI_IO_UART_PASSTHRU = 212,
3427}
3428impl MavTunnelPayloadType {
3429 pub const DEFAULT: Self = Self::MAV_TUNNEL_PAYLOAD_TYPE_UNKNOWN;
3430}
3431impl Default for MavTunnelPayloadType {
3432 fn default() -> Self {
3433 Self::DEFAULT
3434 }
3435}
3436#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3437#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3438#[cfg_attr(feature = "serde", serde(tag = "type"))]
3439#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3440#[repr(u32)]
3441#[doc = "MAVLINK component type reported in HEARTBEAT message. Flight controllers must report the type of the vehicle on which they are mounted (e.g. MAV_TYPE_OCTOROTOR). All other components must report a value appropriate for their type (e.g. a camera must use MAV_TYPE_CAMERA)."]
3442pub enum MavType {
3443 #[doc = "Generic micro air vehicle"]
3444 MAV_TYPE_GENERIC = 0,
3445 #[doc = "Fixed wing aircraft."]
3446 MAV_TYPE_FIXED_WING = 1,
3447 #[doc = "Quadrotor"]
3448 MAV_TYPE_QUADROTOR = 2,
3449 #[doc = "Coaxial helicopter"]
3450 MAV_TYPE_COAXIAL = 3,
3451 #[doc = "Normal helicopter with tail rotor."]
3452 MAV_TYPE_HELICOPTER = 4,
3453 #[doc = "Ground installation"]
3454 MAV_TYPE_ANTENNA_TRACKER = 5,
3455 #[doc = "Operator control unit / ground control station"]
3456 MAV_TYPE_GCS = 6,
3457 #[doc = "Airship, controlled"]
3458 MAV_TYPE_AIRSHIP = 7,
3459 #[doc = "Free balloon, uncontrolled"]
3460 MAV_TYPE_FREE_BALLOON = 8,
3461 #[doc = "Rocket"]
3462 MAV_TYPE_ROCKET = 9,
3463 #[doc = "Ground rover"]
3464 MAV_TYPE_GROUND_ROVER = 10,
3465 #[doc = "Surface vessel, boat, ship"]
3466 MAV_TYPE_SURFACE_BOAT = 11,
3467 #[doc = "Submarine"]
3468 MAV_TYPE_SUBMARINE = 12,
3469 #[doc = "Hexarotor"]
3470 MAV_TYPE_HEXAROTOR = 13,
3471 #[doc = "Octorotor"]
3472 MAV_TYPE_OCTOROTOR = 14,
3473 #[doc = "Tricopter"]
3474 MAV_TYPE_TRICOPTER = 15,
3475 #[doc = "Flapping wing"]
3476 MAV_TYPE_FLAPPING_WING = 16,
3477 #[doc = "Kite"]
3478 MAV_TYPE_KITE = 17,
3479 #[doc = "Onboard companion controller"]
3480 MAV_TYPE_ONBOARD_CONTROLLER = 18,
3481 #[doc = "Two-rotor Tailsitter VTOL that additionally uses control surfaces in vertical operation. Note, value previously named MAV_TYPE_VTOL_DUOROTOR."]
3482 MAV_TYPE_VTOL_TAILSITTER_DUOROTOR = 19,
3483 #[doc = "Quad-rotor Tailsitter VTOL using a V-shaped quad config in vertical operation. Note: value previously named MAV_TYPE_VTOL_QUADROTOR."]
3484 MAV_TYPE_VTOL_TAILSITTER_QUADROTOR = 20,
3485 #[doc = "Tiltrotor VTOL. Fuselage and wings stay (nominally) horizontal in all flight phases. It able to tilt (some) rotors to provide thrust in cruise flight."]
3486 MAV_TYPE_VTOL_TILTROTOR = 21,
3487 #[doc = "VTOL with separate fixed rotors for hover and cruise flight. Fuselage and wings stay (nominally) horizontal in all flight phases."]
3488 MAV_TYPE_VTOL_FIXEDROTOR = 22,
3489 #[doc = "Tailsitter VTOL. Fuselage and wings orientation changes depending on flight phase: vertical for hover, horizontal for cruise. Use more specific VTOL MAV_TYPE_VTOL_TAILSITTER_DUOROTOR or MAV_TYPE_VTOL_TAILSITTER_QUADROTOR if appropriate."]
3490 MAV_TYPE_VTOL_TAILSITTER = 23,
3491 #[doc = "Tiltwing VTOL. Fuselage stays horizontal in all flight phases. The whole wing, along with any attached engine, can tilt between vertical and horizontal mode."]
3492 MAV_TYPE_VTOL_TILTWING = 24,
3493 #[doc = "VTOL reserved 5"]
3494 MAV_TYPE_VTOL_RESERVED5 = 25,
3495 #[doc = "Gimbal"]
3496 MAV_TYPE_GIMBAL = 26,
3497 #[doc = "ADSB system"]
3498 MAV_TYPE_ADSB = 27,
3499 #[doc = "Steerable, nonrigid airfoil"]
3500 MAV_TYPE_PARAFOIL = 28,
3501 #[doc = "Dodecarotor"]
3502 MAV_TYPE_DODECAROTOR = 29,
3503 #[doc = "Camera"]
3504 MAV_TYPE_CAMERA = 30,
3505 #[doc = "Charging station"]
3506 MAV_TYPE_CHARGING_STATION = 31,
3507 #[doc = "FLARM collision avoidance system"]
3508 MAV_TYPE_FLARM = 32,
3509 #[doc = "Servo"]
3510 MAV_TYPE_SERVO = 33,
3511 #[doc = "Open Drone ID. See <https://mavlink.io/en/services/opendroneid.html>."]
3512 MAV_TYPE_ODID = 34,
3513 #[doc = "Decarotor"]
3514 MAV_TYPE_DECAROTOR = 35,
3515 #[doc = "Battery"]
3516 MAV_TYPE_BATTERY = 36,
3517 #[doc = "Parachute"]
3518 MAV_TYPE_PARACHUTE = 37,
3519 #[doc = "Log"]
3520 MAV_TYPE_LOG = 38,
3521 #[doc = "OSD"]
3522 MAV_TYPE_OSD = 39,
3523 #[doc = "IMU"]
3524 MAV_TYPE_IMU = 40,
3525 #[doc = "GPS"]
3526 MAV_TYPE_GPS = 41,
3527 #[doc = "Winch"]
3528 MAV_TYPE_WINCH = 42,
3529 #[doc = "Generic multirotor that does not fit into a specific type or whose type is unknown"]
3530 MAV_TYPE_GENERIC_MULTIROTOR = 43,
3531 #[doc = "Illuminator. An illuminator is a light source that is used for lighting up dark areas external to the sytstem: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light)."]
3532 MAV_TYPE_ILLUMINATOR = 44,
3533 #[doc = "Orbiter spacecraft. Includes satellites orbiting terrestrial and extra-terrestrial bodies. Follows NASA Spacecraft Classification."]
3534 MAV_TYPE_SPACECRAFT_ORBITER = 45,
3535}
3536impl MavType {
3537 pub const DEFAULT: Self = Self::MAV_TYPE_GENERIC;
3538}
3539impl Default for MavType {
3540 fn default() -> Self {
3541 Self::DEFAULT
3542 }
3543}
3544#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3545#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3546#[cfg_attr(feature = "serde", serde(tag = "type"))]
3547#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3548#[repr(u32)]
3549#[doc = "Enumeration of VTOL states"]
3550pub enum MavVtolState {
3551 #[doc = "MAV is not configured as VTOL"]
3552 MAV_VTOL_STATE_UNDEFINED = 0,
3553 #[doc = "VTOL is in transition from multicopter to fixed-wing"]
3554 MAV_VTOL_STATE_TRANSITION_TO_FW = 1,
3555 #[doc = "VTOL is in transition from fixed-wing to multicopter"]
3556 MAV_VTOL_STATE_TRANSITION_TO_MC = 2,
3557 #[doc = "VTOL is in multicopter state"]
3558 MAV_VTOL_STATE_MC = 3,
3559 #[doc = "VTOL is in fixed-wing state"]
3560 MAV_VTOL_STATE_FW = 4,
3561}
3562impl MavVtolState {
3563 pub const DEFAULT: Self = Self::MAV_VTOL_STATE_UNDEFINED;
3564}
3565impl Default for MavVtolState {
3566 fn default() -> Self {
3567 Self::DEFAULT
3568 }
3569}
3570bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Winch status flags used in WINCH_STATUS"] pub struct MavWinchStatusFlag : u32 { # [doc = "Winch is healthy"] const MAV_WINCH_STATUS_HEALTHY = 1 ; # [doc = "Winch line is fully retracted"] const MAV_WINCH_STATUS_FULLY_RETRACTED = 2 ; # [doc = "Winch motor is moving"] const MAV_WINCH_STATUS_MOVING = 4 ; # [doc = "Winch clutch is engaged allowing motor to move freely."] const MAV_WINCH_STATUS_CLUTCH_ENGAGED = 8 ; # [doc = "Winch is locked by locking mechanism."] const MAV_WINCH_STATUS_LOCKED = 16 ; # [doc = "Winch is gravity dropping payload."] const MAV_WINCH_STATUS_DROPPING = 32 ; # [doc = "Winch is arresting payload descent."] const MAV_WINCH_STATUS_ARRESTING = 64 ; # [doc = "Winch is using torque measurements to sense the ground."] const MAV_WINCH_STATUS_GROUND_SENSE = 128 ; # [doc = "Winch is returning to the fully retracted position."] const MAV_WINCH_STATUS_RETRACTING = 256 ; # [doc = "Winch is redelivering the payload. This is a failover state if the line tension goes above a threshold during RETRACTING."] const MAV_WINCH_STATUS_REDELIVER = 512 ; # [doc = "Winch is abandoning the line and possibly payload. Winch unspools the entire calculated line length. This is a failover state from REDELIVER if the number of attempts exceeds a threshold."] const MAV_WINCH_STATUS_ABANDON_LINE = 1024 ; # [doc = "Winch is engaging the locking mechanism."] const MAV_WINCH_STATUS_LOCKING = 2048 ; # [doc = "Winch is spooling on line."] const MAV_WINCH_STATUS_LOAD_LINE = 4096 ; # [doc = "Winch is loading a payload."] const MAV_WINCH_STATUS_LOAD_PAYLOAD = 8192 ; } }
3571impl MavWinchStatusFlag {
3572 pub const DEFAULT: Self = Self::MAV_WINCH_STATUS_HEALTHY;
3573}
3574impl Default for MavWinchStatusFlag {
3575 fn default() -> Self {
3576 Self::DEFAULT
3577 }
3578}
3579#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3580#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3581#[cfg_attr(feature = "serde", serde(tag = "type"))]
3582#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3583#[repr(u32)]
3584pub enum MavlinkDataStreamType {
3585 MAVLINK_DATA_STREAM_IMG_JPEG = 0,
3586 MAVLINK_DATA_STREAM_IMG_BMP = 1,
3587 MAVLINK_DATA_STREAM_IMG_RAW8U = 2,
3588 MAVLINK_DATA_STREAM_IMG_RAW32U = 3,
3589 MAVLINK_DATA_STREAM_IMG_PGM = 4,
3590 MAVLINK_DATA_STREAM_IMG_PNG = 5,
3591}
3592impl MavlinkDataStreamType {
3593 pub const DEFAULT: Self = Self::MAVLINK_DATA_STREAM_IMG_JPEG;
3594}
3595impl Default for MavlinkDataStreamType {
3596 fn default() -> Self {
3597 Self::DEFAULT
3598 }
3599}
3600#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3601#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3602#[cfg_attr(feature = "serde", serde(tag = "type"))]
3603#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3604#[repr(u32)]
3605#[doc = "States of the mission state machine. Note that these states are independent of whether the mission is in a mode that can execute mission items or not (is suspended). They may not all be relevant on all vehicles."]
3606pub enum MissionState {
3607 #[doc = "The mission status reporting is not supported."]
3608 MISSION_STATE_UNKNOWN = 0,
3609 #[doc = "No mission on the vehicle."]
3610 MISSION_STATE_NO_MISSION = 1,
3611 #[doc = "Mission has not started. This is the case after a mission has uploaded but not yet started executing."]
3612 MISSION_STATE_NOT_STARTED = 2,
3613 #[doc = "Mission is active, and will execute mission items when in auto mode."]
3614 MISSION_STATE_ACTIVE = 3,
3615 #[doc = "Mission is paused when in auto mode."]
3616 MISSION_STATE_PAUSED = 4,
3617 #[doc = "Mission has executed all mission items."]
3618 MISSION_STATE_COMPLETE = 5,
3619}
3620impl MissionState {
3621 pub const DEFAULT: Self = Self::MISSION_STATE_UNKNOWN;
3622}
3623impl Default for MissionState {
3624 fn default() -> Self {
3625 Self::DEFAULT
3626 }
3627}
3628#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3629#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3630#[cfg_attr(feature = "serde", serde(tag = "type"))]
3631#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3632#[repr(u32)]
3633#[doc = "Sequence that motors are tested when using MAV_CMD_DO_MOTOR_TEST."]
3634pub enum MotorTestOrder {
3635 #[doc = "Default autopilot motor test method."]
3636 MOTOR_TEST_ORDER_DEFAULT = 0,
3637 #[doc = "Motor numbers are specified as their index in a predefined vehicle-specific sequence."]
3638 MOTOR_TEST_ORDER_SEQUENCE = 1,
3639 #[doc = "Motor numbers are specified as the output as labeled on the board."]
3640 MOTOR_TEST_ORDER_BOARD = 2,
3641}
3642impl MotorTestOrder {
3643 pub const DEFAULT: Self = Self::MOTOR_TEST_ORDER_DEFAULT;
3644}
3645impl Default for MotorTestOrder {
3646 fn default() -> Self {
3647 Self::DEFAULT
3648 }
3649}
3650#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3651#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3652#[cfg_attr(feature = "serde", serde(tag = "type"))]
3653#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3654#[repr(u32)]
3655#[doc = "Defines how throttle value is represented in MAV_CMD_DO_MOTOR_TEST."]
3656pub enum MotorTestThrottleType {
3657 #[doc = "Throttle as a percentage (0 ~ 100)"]
3658 MOTOR_TEST_THROTTLE_PERCENT = 0,
3659 #[doc = "Throttle as an absolute PWM value (normally in range of 1000~2000)."]
3660 MOTOR_TEST_THROTTLE_PWM = 1,
3661 #[doc = "Throttle pass-through from pilot's transmitter."]
3662 MOTOR_TEST_THROTTLE_PILOT = 2,
3663 #[doc = "Per-motor compass calibration test."]
3664 MOTOR_TEST_COMPASS_CAL = 3,
3665}
3666impl MotorTestThrottleType {
3667 pub const DEFAULT: Self = Self::MOTOR_TEST_THROTTLE_PERCENT;
3668}
3669impl Default for MotorTestThrottleType {
3670 fn default() -> Self {
3671 Self::DEFAULT
3672 }
3673}
3674#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3675#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3676#[cfg_attr(feature = "serde", serde(tag = "type"))]
3677#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3678#[repr(u32)]
3679pub enum NavVtolLandOptions {
3680 #[doc = "Default autopilot landing behaviour."]
3681 NAV_VTOL_LAND_OPTIONS_DEFAULT = 0,
3682 #[doc = "Descend in fixed wing mode, transitioning to multicopter mode for vertical landing when close to the ground. The fixed wing descent pattern is at the discretion of the vehicle (e.g. transition altitude, loiter direction, radius, and speed, etc.)."]
3683 NAV_VTOL_LAND_OPTIONS_FW_DESCENT = 1,
3684 #[doc = "Land in multicopter mode on reaching the landing coordinates (the whole landing is by \"hover descent\")."]
3685 NAV_VTOL_LAND_OPTIONS_HOVER_DESCENT = 2,
3686}
3687impl NavVtolLandOptions {
3688 pub const DEFAULT: Self = Self::NAV_VTOL_LAND_OPTIONS_DEFAULT;
3689}
3690impl Default for NavVtolLandOptions {
3691 fn default() -> Self {
3692 Self::DEFAULT
3693 }
3694}
3695#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3696#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3697#[cfg_attr(feature = "serde", serde(tag = "type"))]
3698#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3699#[repr(u32)]
3700#[doc = "Yaw behaviour during orbit flight."]
3701pub enum OrbitYawBehaviour {
3702 #[doc = "Vehicle front points to the center (default)."]
3703 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER = 0,
3704 #[doc = "Vehicle front holds heading when message received."]
3705 ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING = 1,
3706 #[doc = "Yaw uncontrolled."]
3707 ORBIT_YAW_BEHAVIOUR_UNCONTROLLED = 2,
3708 #[doc = "Vehicle front follows flight path (tangential to circle)."]
3709 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE = 3,
3710 #[doc = "Yaw controlled by RC input."]
3711 ORBIT_YAW_BEHAVIOUR_RC_CONTROLLED = 4,
3712 #[doc = "Vehicle uses current yaw behaviour (unchanged). The vehicle-default yaw behaviour is used if this value is specified when orbit is first commanded."]
3713 ORBIT_YAW_BEHAVIOUR_UNCHANGED = 5,
3714}
3715impl OrbitYawBehaviour {
3716 pub const DEFAULT: Self = Self::ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER;
3717}
3718impl Default for OrbitYawBehaviour {
3719 fn default() -> Self {
3720 Self::DEFAULT
3721 }
3722}
3723#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3724#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3725#[cfg_attr(feature = "serde", serde(tag = "type"))]
3726#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3727#[repr(u32)]
3728#[doc = "Parachute actions. Trigger release and enable/disable auto-release."]
3729pub enum ParachuteAction {
3730 #[doc = "Disable auto-release of parachute (i.e. release triggered by crash detectors)."]
3731 PARACHUTE_DISABLE = 0,
3732 #[doc = "Enable auto-release of parachute."]
3733 PARACHUTE_ENABLE = 1,
3734 #[doc = "Release parachute and kill motors."]
3735 PARACHUTE_RELEASE = 2,
3736}
3737impl ParachuteAction {
3738 pub const DEFAULT: Self = Self::PARACHUTE_DISABLE;
3739}
3740impl Default for ParachuteAction {
3741 fn default() -> Self {
3742 Self::DEFAULT
3743 }
3744}
3745#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3746#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3747#[cfg_attr(feature = "serde", serde(tag = "type"))]
3748#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3749#[repr(u32)]
3750#[doc = "Result from PARAM_EXT_SET message."]
3751pub enum ParamAck {
3752 #[doc = "Parameter value ACCEPTED and SET"]
3753 PARAM_ACK_ACCEPTED = 0,
3754 #[doc = "Parameter value UNKNOWN/UNSUPPORTED"]
3755 PARAM_ACK_VALUE_UNSUPPORTED = 1,
3756 #[doc = "Parameter failed to set"]
3757 PARAM_ACK_FAILED = 2,
3758 #[doc = "Parameter value received but not yet set/accepted. A subsequent PARAM_EXT_ACK with the final result will follow once operation is completed. This is returned immediately for parameters that take longer to set, indicating that the the parameter was received and does not need to be resent."]
3759 PARAM_ACK_IN_PROGRESS = 3,
3760}
3761impl ParamAck {
3762 pub const DEFAULT: Self = Self::PARAM_ACK_ACCEPTED;
3763}
3764impl Default for ParamAck {
3765 fn default() -> Self {
3766 Self::DEFAULT
3767 }
3768}
3769bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 9 is set the floats afx afy afz should be interpreted as force instead of acceleration."] pub struct PositionTargetTypemask : u16 { # [doc = "Ignore position x"] const POSITION_TARGET_TYPEMASK_X_IGNORE = 1 ; # [doc = "Ignore position y"] const POSITION_TARGET_TYPEMASK_Y_IGNORE = 2 ; # [doc = "Ignore position z"] const POSITION_TARGET_TYPEMASK_Z_IGNORE = 4 ; # [doc = "Ignore velocity x"] const POSITION_TARGET_TYPEMASK_VX_IGNORE = 8 ; # [doc = "Ignore velocity y"] const POSITION_TARGET_TYPEMASK_VY_IGNORE = 16 ; # [doc = "Ignore velocity z"] const POSITION_TARGET_TYPEMASK_VZ_IGNORE = 32 ; # [doc = "Ignore acceleration x"] const POSITION_TARGET_TYPEMASK_AX_IGNORE = 64 ; # [doc = "Ignore acceleration y"] const POSITION_TARGET_TYPEMASK_AY_IGNORE = 128 ; # [doc = "Ignore acceleration z"] const POSITION_TARGET_TYPEMASK_AZ_IGNORE = 256 ; # [doc = "Use force instead of acceleration"] const POSITION_TARGET_TYPEMASK_FORCE_SET = 512 ; # [doc = "Ignore yaw"] const POSITION_TARGET_TYPEMASK_YAW_IGNORE = 1024 ; # [doc = "Ignore yaw rate"] const POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE = 2048 ; } }
3770impl PositionTargetTypemask {
3771 pub const DEFAULT: Self = Self::POSITION_TARGET_TYPEMASK_X_IGNORE;
3772}
3773impl Default for PositionTargetTypemask {
3774 fn default() -> Self {
3775 Self::DEFAULT
3776 }
3777}
3778#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3779#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3780#[cfg_attr(feature = "serde", serde(tag = "type"))]
3781#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3782#[repr(u32)]
3783#[doc = "Precision land modes (used in MAV_CMD_NAV_LAND)."]
3784pub enum PrecisionLandMode {
3785 #[doc = "Normal (non-precision) landing."]
3786 PRECISION_LAND_MODE_DISABLED = 0,
3787 #[doc = "Use precision landing if beacon detected when land command accepted, otherwise land normally."]
3788 PRECISION_LAND_MODE_OPPORTUNISTIC = 1,
3789 #[doc = "Use precision landing, searching for beacon if not found when land command accepted (land normally if beacon cannot be found)."]
3790 PRECISION_LAND_MODE_REQUIRED = 2,
3791}
3792impl PrecisionLandMode {
3793 pub const DEFAULT: Self = Self::PRECISION_LAND_MODE_DISABLED;
3794}
3795impl Default for PrecisionLandMode {
3796 fn default() -> Self {
3797 Self::DEFAULT
3798 }
3799}
3800#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3801#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3802#[cfg_attr(feature = "serde", serde(tag = "type"))]
3803#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3804#[repr(u32)]
3805#[doc = "Actions for reading and writing plan information (mission, rally points, geofence) between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. (Commonly missions are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.)"]
3806pub enum PreflightStorageMissionAction {
3807 #[doc = "Read current mission data from persistent storage"]
3808 MISSION_READ_PERSISTENT = 0,
3809 #[doc = "Write current mission data to persistent storage"]
3810 MISSION_WRITE_PERSISTENT = 1,
3811 #[doc = "Erase all mission data stored on the vehicle (both persistent and volatile storage)"]
3812 MISSION_RESET_DEFAULT = 2,
3813}
3814impl PreflightStorageMissionAction {
3815 pub const DEFAULT: Self = Self::MISSION_READ_PERSISTENT;
3816}
3817impl Default for PreflightStorageMissionAction {
3818 fn default() -> Self {
3819 Self::DEFAULT
3820 }
3821}
3822#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3823#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3824#[cfg_attr(feature = "serde", serde(tag = "type"))]
3825#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3826#[repr(u32)]
3827#[doc = "Actions for reading/writing parameters between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. (Commonly parameters are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.)"]
3828pub enum PreflightStorageParameterAction {
3829 #[doc = "Read all parameters from persistent storage. Replaces values in volatile storage."]
3830 PARAM_READ_PERSISTENT = 0,
3831 #[doc = "Write all parameter values to persistent storage (flash/EEPROM)"]
3832 PARAM_WRITE_PERSISTENT = 1,
3833 #[doc = "Reset all user configurable parameters to their default value (including airframe selection, sensor calibration data, safety settings, and so on). Does not reset values that contain operation counters and vehicle computed statistics."]
3834 PARAM_RESET_CONFIG_DEFAULT = 2,
3835 #[doc = "Reset only sensor calibration parameters to factory defaults (or firmware default if not available)"]
3836 PARAM_RESET_SENSOR_DEFAULT = 3,
3837 #[doc = "Reset all parameters, including operation counters, to default values"]
3838 PARAM_RESET_ALL_DEFAULT = 4,
3839}
3840impl PreflightStorageParameterAction {
3841 pub const DEFAULT: Self = Self::PARAM_READ_PERSISTENT;
3842}
3843impl Default for PreflightStorageParameterAction {
3844 fn default() -> Self {
3845 Self::DEFAULT
3846 }
3847}
3848#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3849#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3850#[cfg_attr(feature = "serde", serde(tag = "type"))]
3851#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3852#[repr(u32)]
3853#[doc = "RC sub-type of types defined in RC_TYPE. Used in MAV_CMD_START_RX_PAIR. Ignored if value does not correspond to the set RC_TYPE."]
3854pub enum RcSubType {
3855 #[doc = "Spektrum DSM2"]
3856 RC_SUB_TYPE_SPEKTRUM_DSM2 = 0,
3857 #[doc = "Spektrum DSMX"]
3858 RC_SUB_TYPE_SPEKTRUM_DSMX = 1,
3859 #[doc = "Spektrum DSMX8"]
3860 RC_SUB_TYPE_SPEKTRUM_DSMX8 = 2,
3861}
3862impl RcSubType {
3863 pub const DEFAULT: Self = Self::RC_SUB_TYPE_SPEKTRUM_DSM2;
3864}
3865impl Default for RcSubType {
3866 fn default() -> Self {
3867 Self::DEFAULT
3868 }
3869}
3870#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3871#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3872#[cfg_attr(feature = "serde", serde(tag = "type"))]
3873#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3874#[repr(u32)]
3875#[doc = "RC type. Used in MAV_CMD_START_RX_PAIR."]
3876pub enum RcType {
3877 #[doc = "Spektrum"]
3878 RC_TYPE_SPEKTRUM = 0,
3879 #[doc = "CRSF"]
3880 RC_TYPE_CRSF = 1,
3881}
3882impl RcType {
3883 pub const DEFAULT: Self = Self::RC_TYPE_SPEKTRUM;
3884}
3885impl Default for RcType {
3886 fn default() -> Self {
3887 Self::DEFAULT
3888 }
3889}
3890#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3891#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3892#[cfg_attr(feature = "serde", serde(tag = "type"))]
3893#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3894#[repr(u32)]
3895#[doc = "Specifies the conditions under which the MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN command should be accepted."]
3896pub enum RebootShutdownConditions {
3897 #[doc = "Reboot/Shutdown only if allowed by safety checks, such as being landed."]
3898 REBOOT_SHUTDOWN_CONDITIONS_SAFETY_INTERLOCKED = 0,
3899 #[doc = "Force reboot/shutdown of the autopilot/component regardless of system state."]
3900 REBOOT_SHUTDOWN_CONDITIONS_FORCE = 20190226,
3901}
3902impl RebootShutdownConditions {
3903 pub const DEFAULT: Self = Self::REBOOT_SHUTDOWN_CONDITIONS_SAFETY_INTERLOCKED;
3904}
3905impl Default for RebootShutdownConditions {
3906 fn default() -> Self {
3907 Self::DEFAULT
3908 }
3909}
3910#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3911#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3912#[cfg_attr(feature = "serde", serde(tag = "type"))]
3913#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3914#[repr(u32)]
3915#[doc = "RTK GPS baseline coordinate system, used for RTK corrections"]
3916pub enum RtkBaselineCoordinateSystem {
3917 #[doc = "Earth-centered, Earth-fixed"]
3918 RTK_BASELINE_COORDINATE_SYSTEM_ECEF = 0,
3919 #[doc = "RTK basestation centered, north, east, down"]
3920 RTK_BASELINE_COORDINATE_SYSTEM_NED = 1,
3921}
3922impl RtkBaselineCoordinateSystem {
3923 pub const DEFAULT: Self = Self::RTK_BASELINE_COORDINATE_SYSTEM_ECEF;
3924}
3925impl Default for RtkBaselineCoordinateSystem {
3926 fn default() -> Self {
3927 Self::DEFAULT
3928 }
3929}
3930#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3931#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3932#[cfg_attr(feature = "serde", serde(tag = "type"))]
3933#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3934#[repr(u32)]
3935#[doc = "Possible safety switch states."]
3936pub enum SafetySwitchState {
3937 #[doc = "Safety switch is engaged and vehicle should be safe to approach."]
3938 SAFETY_SWITCH_STATE_SAFE = 0,
3939 #[doc = "Safety switch is NOT engaged and motors, propellers and other actuators should be considered active."]
3940 SAFETY_SWITCH_STATE_DANGEROUS = 1,
3941}
3942impl SafetySwitchState {
3943 pub const DEFAULT: Self = Self::SAFETY_SWITCH_STATE_SAFE;
3944}
3945impl Default for SafetySwitchState {
3946 fn default() -> Self {
3947 Self::DEFAULT
3948 }
3949}
3950#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3951#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3952#[cfg_attr(feature = "serde", serde(tag = "type"))]
3953#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3954#[repr(u32)]
3955#[doc = "SERIAL_CONTROL device types"]
3956pub enum SerialControlDev {
3957 #[doc = "First telemetry port"]
3958 SERIAL_CONTROL_DEV_TELEM1 = 0,
3959 #[doc = "Second telemetry port"]
3960 SERIAL_CONTROL_DEV_TELEM2 = 1,
3961 #[doc = "First GPS port"]
3962 SERIAL_CONTROL_DEV_GPS1 = 2,
3963 #[doc = "Second GPS port"]
3964 SERIAL_CONTROL_DEV_GPS2 = 3,
3965 #[doc = "system shell"]
3966 SERIAL_CONTROL_DEV_SHELL = 10,
3967 #[doc = "SERIAL0"]
3968 SERIAL_CONTROL_SERIAL0 = 100,
3969 #[doc = "SERIAL1"]
3970 SERIAL_CONTROL_SERIAL1 = 101,
3971 #[doc = "SERIAL2"]
3972 SERIAL_CONTROL_SERIAL2 = 102,
3973 #[doc = "SERIAL3"]
3974 SERIAL_CONTROL_SERIAL3 = 103,
3975 #[doc = "SERIAL4"]
3976 SERIAL_CONTROL_SERIAL4 = 104,
3977 #[doc = "SERIAL5"]
3978 SERIAL_CONTROL_SERIAL5 = 105,
3979 #[doc = "SERIAL6"]
3980 SERIAL_CONTROL_SERIAL6 = 106,
3981 #[doc = "SERIAL7"]
3982 SERIAL_CONTROL_SERIAL7 = 107,
3983 #[doc = "SERIAL8"]
3984 SERIAL_CONTROL_SERIAL8 = 108,
3985 #[doc = "SERIAL9"]
3986 SERIAL_CONTROL_SERIAL9 = 109,
3987}
3988impl SerialControlDev {
3989 pub const DEFAULT: Self = Self::SERIAL_CONTROL_DEV_TELEM1;
3990}
3991impl Default for SerialControlDev {
3992 fn default() -> Self {
3993 Self::DEFAULT
3994 }
3995}
3996bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "SERIAL_CONTROL flags (bitmask)"] pub struct SerialControlFlag : u8 { # [doc = "Set if this is a reply"] const SERIAL_CONTROL_FLAG_REPLY = 1 ; # [doc = "Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message"] const SERIAL_CONTROL_FLAG_RESPOND = 2 ; # [doc = "Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set"] const SERIAL_CONTROL_FLAG_EXCLUSIVE = 4 ; # [doc = "Block on writes to the serial port"] const SERIAL_CONTROL_FLAG_BLOCKING = 8 ; # [doc = "Send multiple replies until port is drained"] const SERIAL_CONTROL_FLAG_MULTI = 16 ; } }
3997impl SerialControlFlag {
3998 pub const DEFAULT: Self = Self::SERIAL_CONTROL_FLAG_REPLY;
3999}
4000impl Default for SerialControlFlag {
4001 fn default() -> Self {
4002 Self::DEFAULT
4003 }
4004}
4005#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4006#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4007#[cfg_attr(feature = "serde", serde(tag = "type"))]
4008#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4009#[repr(u32)]
4010#[doc = "Focus types for MAV_CMD_SET_CAMERA_FOCUS"]
4011pub enum SetFocusType {
4012 #[doc = "Focus one step increment (-1 for focusing in, 1 for focusing out towards infinity)."]
4013 FOCUS_TYPE_STEP = 0,
4014 #[doc = "Continuous normalized focus in/out rate until stopped. Range -1..1, negative: in, positive: out towards infinity, 0 to stop focusing. Other values should be clipped to the range."]
4015 FOCUS_TYPE_CONTINUOUS = 1,
4016 #[doc = "Focus value as proportion of full camera focus range (a value between 0.0 and 100.0)"]
4017 FOCUS_TYPE_RANGE = 2,
4018 #[doc = "Focus value in metres. Note that there is no message to get the valid focus range of the camera, so this can type can only be used for cameras where the range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera)."]
4019 FOCUS_TYPE_METERS = 3,
4020 #[doc = "Focus automatically."]
4021 FOCUS_TYPE_AUTO = 4,
4022 #[doc = "Single auto focus. Mainly used for still pictures. Usually abbreviated as AF-S."]
4023 FOCUS_TYPE_AUTO_SINGLE = 5,
4024 #[doc = "Continuous auto focus. Mainly used for dynamic scenes. Abbreviated as AF-C."]
4025 FOCUS_TYPE_AUTO_CONTINUOUS = 6,
4026}
4027impl SetFocusType {
4028 pub const DEFAULT: Self = Self::FOCUS_TYPE_STEP;
4029}
4030impl Default for SetFocusType {
4031 fn default() -> Self {
4032 Self::DEFAULT
4033 }
4034}
4035#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4036#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4037#[cfg_attr(feature = "serde", serde(tag = "type"))]
4038#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4039#[repr(u32)]
4040#[doc = "Speed setpoint types used in MAV_CMD_DO_CHANGE_SPEED"]
4041pub enum SpeedType {
4042 #[doc = "Airspeed"]
4043 SPEED_TYPE_AIRSPEED = 0,
4044 #[doc = "Groundspeed"]
4045 SPEED_TYPE_GROUNDSPEED = 1,
4046 #[doc = "Climb speed"]
4047 SPEED_TYPE_CLIMB_SPEED = 2,
4048 #[doc = "Descent speed"]
4049 SPEED_TYPE_DESCENT_SPEED = 3,
4050}
4051impl SpeedType {
4052 pub const DEFAULT: Self = Self::SPEED_TYPE_AIRSPEED;
4053}
4054impl Default for SpeedType {
4055 fn default() -> Self {
4056 Self::DEFAULT
4057 }
4058}
4059#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4060#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4061#[cfg_attr(feature = "serde", serde(tag = "type"))]
4062#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4063#[repr(u32)]
4064#[doc = "Flags to indicate the status of camera storage."]
4065pub enum StorageStatus {
4066 #[doc = "Storage is missing (no microSD card loaded for example.)"]
4067 STORAGE_STATUS_EMPTY = 0,
4068 #[doc = "Storage present but unformatted."]
4069 STORAGE_STATUS_UNFORMATTED = 1,
4070 #[doc = "Storage present and ready."]
4071 STORAGE_STATUS_READY = 2,
4072 #[doc = "Camera does not supply storage status information. Capacity information in STORAGE_INFORMATION fields will be ignored."]
4073 STORAGE_STATUS_NOT_SUPPORTED = 3,
4074}
4075impl StorageStatus {
4076 pub const DEFAULT: Self = Self::STORAGE_STATUS_EMPTY;
4077}
4078impl Default for StorageStatus {
4079 fn default() -> Self {
4080 Self::DEFAULT
4081 }
4082}
4083#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4084#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4085#[cfg_attr(feature = "serde", serde(tag = "type"))]
4086#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4087#[repr(u32)]
4088#[doc = "Flags to indicate the type of storage."]
4089pub enum StorageType {
4090 #[doc = "Storage type is not known."]
4091 STORAGE_TYPE_UNKNOWN = 0,
4092 #[doc = "Storage type is USB device."]
4093 STORAGE_TYPE_USB_STICK = 1,
4094 #[doc = "Storage type is SD card."]
4095 STORAGE_TYPE_SD = 2,
4096 #[doc = "Storage type is microSD card."]
4097 STORAGE_TYPE_MICROSD = 3,
4098 #[doc = "Storage type is CFast."]
4099 STORAGE_TYPE_CF = 4,
4100 #[doc = "Storage type is CFexpress."]
4101 STORAGE_TYPE_CFE = 5,
4102 #[doc = "Storage type is XQD."]
4103 STORAGE_TYPE_XQD = 6,
4104 #[doc = "Storage type is HD mass storage type."]
4105 STORAGE_TYPE_HD = 7,
4106 #[doc = "Storage type is other, not listed type."]
4107 STORAGE_TYPE_OTHER = 254,
4108}
4109impl StorageType {
4110 pub const DEFAULT: Self = Self::STORAGE_TYPE_UNKNOWN;
4111}
4112impl Default for StorageType {
4113 fn default() -> Self {
4114 Self::DEFAULT
4115 }
4116}
4117bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to indicate usage for a particular storage (see STORAGE_INFORMATION.storage_usage and MAV_CMD_SET_STORAGE_USAGE)."] pub struct StorageUsageFlag : u8 { # [doc = "Always set to 1 (indicates STORAGE_INFORMATION.storage_usage is supported)."] const STORAGE_USAGE_FLAG_SET = 1 ; # [doc = "Storage for saving photos."] const STORAGE_USAGE_FLAG_PHOTO = 2 ; # [doc = "Storage for saving videos."] const STORAGE_USAGE_FLAG_VIDEO = 4 ; # [doc = "Storage for saving logs."] const STORAGE_USAGE_FLAG_LOGS = 8 ; } }
4118impl StorageUsageFlag {
4119 pub const DEFAULT: Self = Self::STORAGE_USAGE_FLAG_SET;
4120}
4121impl Default for StorageUsageFlag {
4122 fn default() -> Self {
4123 Self::DEFAULT
4124 }
4125}
4126#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4127#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4128#[cfg_attr(feature = "serde", serde(tag = "type"))]
4129#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4130#[repr(u32)]
4131#[doc = "Tune formats (used for vehicle buzzer/tone generation)."]
4132pub enum TuneFormat {
4133 #[doc = "Format is QBasic 1.1 Play: <https://www.qbasic.net/en/reference/qb11/Statement/PLAY-006.htm>."]
4134 TUNE_FORMAT_QBASIC1_1 = 1,
4135 #[doc = "Format is Modern Music Markup Language (MML): <https://en.wikipedia.org/wiki/Music_Macro_Language#Modern_MML>."]
4136 TUNE_FORMAT_MML_MODERN = 2,
4137}
4138impl TuneFormat {
4139 pub const DEFAULT: Self = Self::TUNE_FORMAT_QBASIC1_1;
4140}
4141impl Default for TuneFormat {
4142 fn default() -> Self {
4143 Self::DEFAULT
4144 }
4145}
4146#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4147#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4148#[cfg_attr(feature = "serde", serde(tag = "type"))]
4149#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4150#[repr(u32)]
4151#[doc = "Generalized UAVCAN node health"]
4152pub enum UavcanNodeHealth {
4153 #[doc = "The node is functioning properly."]
4154 UAVCAN_NODE_HEALTH_OK = 0,
4155 #[doc = "A critical parameter went out of range or the node has encountered a minor failure."]
4156 UAVCAN_NODE_HEALTH_WARNING = 1,
4157 #[doc = "The node has encountered a major failure."]
4158 UAVCAN_NODE_HEALTH_ERROR = 2,
4159 #[doc = "The node has suffered a fatal malfunction."]
4160 UAVCAN_NODE_HEALTH_CRITICAL = 3,
4161}
4162impl UavcanNodeHealth {
4163 pub const DEFAULT: Self = Self::UAVCAN_NODE_HEALTH_OK;
4164}
4165impl Default for UavcanNodeHealth {
4166 fn default() -> Self {
4167 Self::DEFAULT
4168 }
4169}
4170#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4171#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4172#[cfg_attr(feature = "serde", serde(tag = "type"))]
4173#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4174#[repr(u32)]
4175#[doc = "Generalized UAVCAN node mode"]
4176pub enum UavcanNodeMode {
4177 #[doc = "The node is performing its primary functions."]
4178 UAVCAN_NODE_MODE_OPERATIONAL = 0,
4179 #[doc = "The node is initializing; this mode is entered immediately after startup."]
4180 UAVCAN_NODE_MODE_INITIALIZATION = 1,
4181 #[doc = "The node is under maintenance."]
4182 UAVCAN_NODE_MODE_MAINTENANCE = 2,
4183 #[doc = "The node is in the process of updating its software."]
4184 UAVCAN_NODE_MODE_SOFTWARE_UPDATE = 3,
4185 #[doc = "The node is no longer available online."]
4186 UAVCAN_NODE_MODE_OFFLINE = 7,
4187}
4188impl UavcanNodeMode {
4189 pub const DEFAULT: Self = Self::UAVCAN_NODE_MODE_OPERATIONAL;
4190}
4191impl Default for UavcanNodeMode {
4192 fn default() -> Self {
4193 Self::DEFAULT
4194 }
4195}
4196#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4197#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4198#[cfg_attr(feature = "serde", serde(tag = "type"))]
4199#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4200#[repr(u32)]
4201#[doc = "Emergency status encoding"]
4202pub enum UavionixAdsbEmergencyStatus {
4203 UAVIONIX_ADSB_OUT_NO_EMERGENCY = 0,
4204 UAVIONIX_ADSB_OUT_GENERAL_EMERGENCY = 1,
4205 UAVIONIX_ADSB_OUT_LIFEGUARD_EMERGENCY = 2,
4206 UAVIONIX_ADSB_OUT_MINIMUM_FUEL_EMERGENCY = 3,
4207 UAVIONIX_ADSB_OUT_NO_COMM_EMERGENCY = 4,
4208 UAVIONIX_ADSB_OUT_UNLAWFUL_INTERFERANCE_EMERGENCY = 5,
4209 UAVIONIX_ADSB_OUT_DOWNED_AIRCRAFT_EMERGENCY = 6,
4210 UAVIONIX_ADSB_OUT_RESERVED = 7,
4211}
4212impl UavionixAdsbEmergencyStatus {
4213 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_NO_EMERGENCY;
4214}
4215impl Default for UavionixAdsbEmergencyStatus {
4216 fn default() -> Self {
4217 Self::DEFAULT
4218 }
4219}
4220#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4221#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4222#[cfg_attr(feature = "serde", serde(tag = "type"))]
4223#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4224#[repr(u32)]
4225#[doc = "Definitions for aircraft size"]
4226pub enum UavionixAdsbOutCfgAircraftSize {
4227 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_NO_DATA = 0,
4228 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L15M_W23M = 1,
4229 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L25M_W28P5M = 2,
4230 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L25_34M = 3,
4231 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L35_33M = 4,
4232 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L35_38M = 5,
4233 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L45_39P5M = 6,
4234 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L45_45M = 7,
4235 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L55_45M = 8,
4236 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L55_52M = 9,
4237 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L65_59P5M = 10,
4238 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L65_67M = 11,
4239 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L75_W72P5M = 12,
4240 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L75_W80M = 13,
4241 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L85_W80M = 14,
4242 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L85_W90M = 15,
4243}
4244impl UavionixAdsbOutCfgAircraftSize {
4245 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_NO_DATA;
4246}
4247impl Default for UavionixAdsbOutCfgAircraftSize {
4248 fn default() -> Self {
4249 Self::DEFAULT
4250 }
4251}
4252#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4253#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4254#[cfg_attr(feature = "serde", serde(tag = "type"))]
4255#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4256#[repr(u32)]
4257#[doc = "GPS lataral offset encoding"]
4258pub enum UavionixAdsbOutCfgGpsOffsetLat {
4259 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_NO_DATA = 0,
4260 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_2M = 1,
4261 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_4M = 2,
4262 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_6M = 3,
4263 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_0M = 4,
4264 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_2M = 5,
4265 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_4M = 6,
4266 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_6M = 7,
4267}
4268impl UavionixAdsbOutCfgGpsOffsetLat {
4269 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_NO_DATA;
4270}
4271impl Default for UavionixAdsbOutCfgGpsOffsetLat {
4272 fn default() -> Self {
4273 Self::DEFAULT
4274 }
4275}
4276#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4277#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4278#[cfg_attr(feature = "serde", serde(tag = "type"))]
4279#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4280#[repr(u32)]
4281#[doc = "GPS longitudinal offset encoding"]
4282pub enum UavionixAdsbOutCfgGpsOffsetLon {
4283 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_NO_DATA = 0,
4284 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_APPLIED_BY_SENSOR = 1,
4285}
4286impl UavionixAdsbOutCfgGpsOffsetLon {
4287 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_NO_DATA;
4288}
4289impl Default for UavionixAdsbOutCfgGpsOffsetLon {
4290 fn default() -> Self {
4291 Self::DEFAULT
4292 }
4293}
4294bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "State flags for ADS-B transponder dynamic report"] pub struct UavionixAdsbOutControlState : u8 { const UAVIONIX_ADSB_OUT_CONTROL_STATE_EXTERNAL_BARO_CROSSCHECKED = 1 ; const UAVIONIX_ADSB_OUT_CONTROL_STATE_ON_GROUND = 4 ; const UAVIONIX_ADSB_OUT_CONTROL_STATE_IDENT_BUTTON_ACTIVE = 8 ; const UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_A_ENABLED = 16 ; const UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_C_ENABLED = 32 ; const UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_S_ENABLED = 64 ; const UAVIONIX_ADSB_OUT_CONTROL_STATE_1090ES_TX_ENABLED = 128 ; } }
4295impl UavionixAdsbOutControlState {
4296 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_CONTROL_STATE_EXTERNAL_BARO_CROSSCHECKED;
4297}
4298impl Default for UavionixAdsbOutControlState {
4299 fn default() -> Self {
4300 Self::DEFAULT
4301 }
4302}
4303#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4304#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4305#[cfg_attr(feature = "serde", serde(tag = "type"))]
4306#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4307#[repr(u32)]
4308#[doc = "Status for ADS-B transponder dynamic input"]
4309pub enum UavionixAdsbOutDynamicGpsFix {
4310 UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_NONE_0 = 0,
4311 UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_NONE_1 = 1,
4312 UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_2D = 2,
4313 UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_3D = 3,
4314 UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_DGPS = 4,
4315 UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_RTK = 5,
4316}
4317impl UavionixAdsbOutDynamicGpsFix {
4318 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_NONE_0;
4319}
4320impl Default for UavionixAdsbOutDynamicGpsFix {
4321 fn default() -> Self {
4322 Self::DEFAULT
4323 }
4324}
4325bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "State flags for ADS-B transponder dynamic report"] pub struct UavionixAdsbOutDynamicState : u16 { const UAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE = 1 ; const UAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED = 2 ; const UAVIONIX_ADSB_OUT_DYNAMIC_STATE_NICBARO_CROSSCHECKED = 4 ; const UAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND = 8 ; const UAVIONIX_ADSB_OUT_DYNAMIC_STATE_IDENT = 16 ; } }
4326impl UavionixAdsbOutDynamicState {
4327 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE;
4328}
4329impl Default for UavionixAdsbOutDynamicState {
4330 fn default() -> Self {
4331 Self::DEFAULT
4332 }
4333}
4334bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Transceiver RF control flags for ADS-B transponder dynamic reports"] pub struct UavionixAdsbOutRfSelect : u8 { const UAVIONIX_ADSB_OUT_RF_SELECT_RX_ENABLED = 1 ; const UAVIONIX_ADSB_OUT_RF_SELECT_TX_ENABLED = 2 ; } }
4335impl UavionixAdsbOutRfSelect {
4336 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_RF_SELECT_RX_ENABLED;
4337}
4338impl Default for UavionixAdsbOutRfSelect {
4339 fn default() -> Self {
4340 Self::DEFAULT
4341 }
4342}
4343bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "State flags for ADS-B transponder fault report"] pub struct UavionixAdsbOutStatusFault : u8 { const UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL = 8 ; const UAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_NO_POS = 16 ; const UAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_UNAVAIL = 32 ; const UAVIONIX_ADSB_OUT_STATUS_FAULT_TX_SYSTEM_FAIL = 64 ; const UAVIONIX_ADSB_OUT_STATUS_FAULT_MAINT_REQ = 128 ; } }
4344impl UavionixAdsbOutStatusFault {
4345 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL;
4346}
4347impl Default for UavionixAdsbOutStatusFault {
4348 fn default() -> Self {
4349 Self::DEFAULT
4350 }
4351}
4352#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4353#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4354#[cfg_attr(feature = "serde", serde(tag = "type"))]
4355#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4356#[repr(u32)]
4357#[doc = "State flags for ADS-B transponder status report"]
4358pub enum UavionixAdsbOutStatusNicNacp {
4359 UAVIONIX_ADSB_NIC_CR_20_NM = 1,
4360 UAVIONIX_ADSB_NIC_CR_8_NM = 2,
4361 UAVIONIX_ADSB_NIC_CR_4_NM = 3,
4362 UAVIONIX_ADSB_NIC_CR_2_NM = 4,
4363 UAVIONIX_ADSB_NIC_CR_1_NM = 5,
4364 UAVIONIX_ADSB_NIC_CR_0_3_NM = 6,
4365 UAVIONIX_ADSB_NIC_CR_0_2_NM = 7,
4366 UAVIONIX_ADSB_NIC_CR_0_1_NM = 8,
4367 UAVIONIX_ADSB_NIC_CR_75_M = 9,
4368 UAVIONIX_ADSB_NIC_CR_25_M = 10,
4369 UAVIONIX_ADSB_NIC_CR_7_5_M = 11,
4370 UAVIONIX_ADSB_NACP_EPU_10_NM = 16,
4371 UAVIONIX_ADSB_NACP_EPU_4_NM = 32,
4372 UAVIONIX_ADSB_NACP_EPU_2_NM = 48,
4373 UAVIONIX_ADSB_NACP_EPU_1_NM = 64,
4374 UAVIONIX_ADSB_NACP_EPU_0_5_NM = 80,
4375 UAVIONIX_ADSB_NACP_EPU_0_3_NM = 96,
4376 UAVIONIX_ADSB_NACP_EPU_0_1_NM = 112,
4377 UAVIONIX_ADSB_NACP_EPU_0_05_NM = 128,
4378 UAVIONIX_ADSB_NACP_EPU_30_M = 144,
4379 UAVIONIX_ADSB_NACP_EPU_10_M = 160,
4380 UAVIONIX_ADSB_NACP_EPU_3_M = 176,
4381}
4382impl UavionixAdsbOutStatusNicNacp {
4383 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_NIC_CR_20_NM;
4384}
4385impl Default for UavionixAdsbOutStatusNicNacp {
4386 fn default() -> Self {
4387 Self::DEFAULT
4388 }
4389}
4390bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "State flags for ADS-B transponder status report"] pub struct UavionixAdsbOutStatusState : u8 { const UAVIONIX_ADSB_OUT_STATUS_STATE_ON_GROUND = 1 ; const UAVIONIX_ADSB_OUT_STATUS_STATE_INTERROGATED_SINCE_LAST = 2 ; const UAVIONIX_ADSB_OUT_STATUS_STATE_XBIT_ENABLED = 4 ; const UAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE = 8 ; const UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED = 16 ; const UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED = 32 ; const UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED = 64 ; const UAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED = 128 ; } }
4391impl UavionixAdsbOutStatusState {
4392 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_STATUS_STATE_ON_GROUND;
4393}
4394impl Default for UavionixAdsbOutStatusState {
4395 fn default() -> Self {
4396 Self::DEFAULT
4397 }
4398}
4399bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Status flags for ADS-B transponder dynamic output"] pub struct UavionixAdsbRfHealth : u8 { const UAVIONIX_ADSB_RF_HEALTH_OK = 1 ; const UAVIONIX_ADSB_RF_HEALTH_FAIL_TX = 2 ; const UAVIONIX_ADSB_RF_HEALTH_FAIL_RX = 16 ; } }
4400impl UavionixAdsbRfHealth {
4401 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_RF_HEALTH_OK;
4402}
4403impl Default for UavionixAdsbRfHealth {
4404 fn default() -> Self {
4405 Self::DEFAULT
4406 }
4407}
4408bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "State flags for X-Bit and reserved fields."] pub struct UavionixAdsbXbit : u8 { const UAVIONIX_ADSB_XBIT_ENABLED = 128 ; } }
4409impl UavionixAdsbXbit {
4410 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_XBIT_ENABLED;
4411}
4412impl Default for UavionixAdsbXbit {
4413 fn default() -> Self {
4414 Self::DEFAULT
4415 }
4416}
4417bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags for the global position report."] pub struct UtmDataAvailFlags : u8 { # [doc = "The field time contains valid data."] const UTM_DATA_AVAIL_FLAGS_TIME_VALID = 1 ; # [doc = "The field uas_id contains valid data."] const UTM_DATA_AVAIL_FLAGS_UAS_ID_AVAILABLE = 2 ; # [doc = "The fields lat, lon and h_acc contain valid data."] const UTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLE = 4 ; # [doc = "The fields alt and v_acc contain valid data."] const UTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLE = 8 ; # [doc = "The field relative_alt contains valid data."] const UTM_DATA_AVAIL_FLAGS_RELATIVE_ALTITUDE_AVAILABLE = 16 ; # [doc = "The fields vx and vy contain valid data."] const UTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLE = 32 ; # [doc = "The field vz contains valid data."] const UTM_DATA_AVAIL_FLAGS_VERTICAL_VELO_AVAILABLE = 64 ; # [doc = "The fields next_lat, next_lon and next_alt contain valid data."] const UTM_DATA_AVAIL_FLAGS_NEXT_WAYPOINT_AVAILABLE = 128 ; } }
4418impl UtmDataAvailFlags {
4419 pub const DEFAULT: Self = Self::UTM_DATA_AVAIL_FLAGS_TIME_VALID;
4420}
4421impl Default for UtmDataAvailFlags {
4422 fn default() -> Self {
4423 Self::DEFAULT
4424 }
4425}
4426#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4427#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4428#[cfg_attr(feature = "serde", serde(tag = "type"))]
4429#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4430#[repr(u32)]
4431#[doc = "Airborne status of UAS."]
4432pub enum UtmFlightState {
4433 #[doc = "The flight state can't be determined."]
4434 UTM_FLIGHT_STATE_UNKNOWN = 1,
4435 #[doc = "UAS on ground."]
4436 UTM_FLIGHT_STATE_GROUND = 2,
4437 #[doc = "UAS airborne."]
4438 UTM_FLIGHT_STATE_AIRBORNE = 3,
4439 #[doc = "UAS is in an emergency flight state."]
4440 UTM_FLIGHT_STATE_EMERGENCY = 16,
4441 #[doc = "UAS has no active controls."]
4442 UTM_FLIGHT_STATE_NOCTRL = 32,
4443}
4444impl UtmFlightState {
4445 pub const DEFAULT: Self = Self::UTM_FLIGHT_STATE_UNKNOWN;
4446}
4447impl Default for UtmFlightState {
4448 fn default() -> Self {
4449 Self::DEFAULT
4450 }
4451}
4452#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4453#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4454#[cfg_attr(feature = "serde", serde(tag = "type"))]
4455#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4456#[repr(u32)]
4457#[doc = "Video stream encodings"]
4458pub enum VideoStreamEncoding {
4459 #[doc = "Stream encoding is unknown"]
4460 VIDEO_STREAM_ENCODING_UNKNOWN = 0,
4461 #[doc = "Stream encoding is H.264"]
4462 VIDEO_STREAM_ENCODING_H264 = 1,
4463 #[doc = "Stream encoding is H.265"]
4464 VIDEO_STREAM_ENCODING_H265 = 2,
4465}
4466impl VideoStreamEncoding {
4467 pub const DEFAULT: Self = Self::VIDEO_STREAM_ENCODING_UNKNOWN;
4468}
4469impl Default for VideoStreamEncoding {
4470 fn default() -> Self {
4471 Self::DEFAULT
4472 }
4473}
4474bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Stream status flags (Bitmap)"] pub struct VideoStreamStatusFlags : u16 { # [doc = "Stream is active (running)"] const VIDEO_STREAM_STATUS_FLAGS_RUNNING = 1 ; # [doc = "Stream is thermal imaging"] const VIDEO_STREAM_STATUS_FLAGS_THERMAL = 2 ; # [doc = "Stream can report absolute thermal range (see CAMERA_THERMAL_RANGE)."] const VIDEO_STREAM_STATUS_FLAGS_THERMAL_RANGE_ENABLED = 4 ; } }
4475impl VideoStreamStatusFlags {
4476 pub const DEFAULT: Self = Self::VIDEO_STREAM_STATUS_FLAGS_RUNNING;
4477}
4478impl Default for VideoStreamStatusFlags {
4479 fn default() -> Self {
4480 Self::DEFAULT
4481 }
4482}
4483#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4484#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4485#[cfg_attr(feature = "serde", serde(tag = "type"))]
4486#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4487#[repr(u32)]
4488#[doc = "Video stream types"]
4489pub enum VideoStreamType {
4490 #[doc = "Stream is RTSP"]
4491 VIDEO_STREAM_TYPE_RTSP = 0,
4492 #[doc = "Stream is RTP UDP (URI gives the port number)"]
4493 VIDEO_STREAM_TYPE_RTPUDP = 1,
4494 #[doc = "Stream is MPEG on TCP"]
4495 VIDEO_STREAM_TYPE_TCP_MPEG = 2,
4496 #[doc = "Stream is MPEG TS (URI gives the port number)"]
4497 VIDEO_STREAM_TYPE_MPEG_TS = 3,
4498}
4499impl VideoStreamType {
4500 pub const DEFAULT: Self = Self::VIDEO_STREAM_TYPE_RTSP;
4501}
4502impl Default for VideoStreamType {
4503 fn default() -> Self {
4504 Self::DEFAULT
4505 }
4506}
4507#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4508#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4509#[cfg_attr(feature = "serde", serde(tag = "type"))]
4510#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4511#[repr(u32)]
4512#[doc = "Direction of VTOL transition"]
4513pub enum VtolTransitionHeading {
4514 #[doc = "Respect the heading configuration of the vehicle."]
4515 VTOL_TRANSITION_HEADING_VEHICLE_DEFAULT = 0,
4516 #[doc = "Use the heading pointing towards the next waypoint."]
4517 VTOL_TRANSITION_HEADING_NEXT_WAYPOINT = 1,
4518 #[doc = "Use the heading on takeoff (while sitting on the ground)."]
4519 VTOL_TRANSITION_HEADING_TAKEOFF = 2,
4520 #[doc = "Use the specified heading in parameter 4."]
4521 VTOL_TRANSITION_HEADING_SPECIFIED = 3,
4522 #[doc = "Use the current heading when reaching takeoff altitude (potentially facing the wind when weather-vaning is active)."]
4523 VTOL_TRANSITION_HEADING_ANY = 4,
4524}
4525impl VtolTransitionHeading {
4526 pub const DEFAULT: Self = Self::VTOL_TRANSITION_HEADING_VEHICLE_DEFAULT;
4527}
4528impl Default for VtolTransitionHeading {
4529 fn default() -> Self {
4530 Self::DEFAULT
4531 }
4532}
4533#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4534#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4535#[cfg_attr(feature = "serde", serde(tag = "type"))]
4536#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4537#[repr(u32)]
4538#[doc = "WiFi Mode."]
4539pub enum WifiConfigApMode {
4540 #[doc = "WiFi mode is undefined."]
4541 WIFI_CONFIG_AP_MODE_UNDEFINED = 0,
4542 #[doc = "WiFi configured as an access point."]
4543 WIFI_CONFIG_AP_MODE_AP = 1,
4544 #[doc = "WiFi configured as a station connected to an existing local WiFi network."]
4545 WIFI_CONFIG_AP_MODE_STATION = 2,
4546 #[doc = "WiFi disabled."]
4547 WIFI_CONFIG_AP_MODE_DISABLED = 3,
4548}
4549impl WifiConfigApMode {
4550 pub const DEFAULT: Self = Self::WIFI_CONFIG_AP_MODE_UNDEFINED;
4551}
4552impl Default for WifiConfigApMode {
4553 fn default() -> Self {
4554 Self::DEFAULT
4555 }
4556}
4557#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4558#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4559#[cfg_attr(feature = "serde", serde(tag = "type"))]
4560#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4561#[repr(u32)]
4562#[doc = "Possible responses from a WIFI_CONFIG_AP message."]
4563pub enum WifiConfigApResponse {
4564 #[doc = "Undefined response. Likely an indicative of a system that doesn't support this request."]
4565 WIFI_CONFIG_AP_RESPONSE_UNDEFINED = 0,
4566 #[doc = "Changes accepted."]
4567 WIFI_CONFIG_AP_RESPONSE_ACCEPTED = 1,
4568 #[doc = "Changes rejected."]
4569 WIFI_CONFIG_AP_RESPONSE_REJECTED = 2,
4570 #[doc = "Invalid Mode."]
4571 WIFI_CONFIG_AP_RESPONSE_MODE_ERROR = 3,
4572 #[doc = "Invalid SSID."]
4573 WIFI_CONFIG_AP_RESPONSE_SSID_ERROR = 4,
4574 #[doc = "Invalid Password."]
4575 WIFI_CONFIG_AP_RESPONSE_PASSWORD_ERROR = 5,
4576}
4577impl WifiConfigApResponse {
4578 pub const DEFAULT: Self = Self::WIFI_CONFIG_AP_RESPONSE_UNDEFINED;
4579}
4580impl Default for WifiConfigApResponse {
4581 fn default() -> Self {
4582 Self::DEFAULT
4583 }
4584}
4585#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4586#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4587#[cfg_attr(feature = "serde", serde(tag = "type"))]
4588#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4589#[repr(u32)]
4590#[doc = "Winch actions."]
4591pub enum WinchActions {
4592 #[doc = "Allow motor to freewheel."]
4593 WINCH_RELAXED = 0,
4594 #[doc = "Wind or unwind specified length of line, optionally using specified rate."]
4595 WINCH_RELATIVE_LENGTH_CONTROL = 1,
4596 #[doc = "Wind or unwind line at specified rate."]
4597 WINCH_RATE_CONTROL = 2,
4598 #[doc = "Perform the locking sequence to relieve motor while in the fully retracted position. Only action and instance command parameters are used, others are ignored."]
4599 WINCH_LOCK = 3,
4600 #[doc = "Sequence of drop, slow down, touch down, reel up, lock. Only action and instance command parameters are used, others are ignored."]
4601 WINCH_DELIVER = 4,
4602 #[doc = "Engage motor and hold current position. Only action and instance command parameters are used, others are ignored."]
4603 WINCH_HOLD = 5,
4604 #[doc = "Return the reel to the fully retracted position. Only action and instance command parameters are used, others are ignored."]
4605 WINCH_RETRACT = 6,
4606 #[doc = "Load the reel with line. The winch will calculate the total loaded length and stop when the tension exceeds a threshold. Only action and instance command parameters are used, others are ignored."]
4607 WINCH_LOAD_LINE = 7,
4608 #[doc = "Spool out the entire length of the line. Only action and instance command parameters are used, others are ignored."]
4609 WINCH_ABANDON_LINE = 8,
4610 #[doc = "Spools out just enough to present the hook to the user to load the payload. Only action and instance command parameters are used, others are ignored"]
4611 WINCH_LOAD_PAYLOAD = 9,
4612}
4613impl WinchActions {
4614 pub const DEFAULT: Self = Self::WINCH_RELAXED;
4615}
4616impl Default for WinchActions {
4617 fn default() -> Self {
4618 Self::DEFAULT
4619 }
4620}
4621#[doc = "id: 140"]
4622#[doc = "Set the vehicle attitude and body angular rates."]
4623#[derive(Debug, Clone, PartialEq)]
4624#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4625#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4626pub struct ACTUATOR_CONTROL_TARGET_DATA {
4627 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
4628 pub time_usec: u64,
4629 #[doc = "Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs."]
4630 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
4631 pub controls: [f32; 8],
4632 #[doc = "Actuator group. The \"_mlx\" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances."]
4633 pub group_mlx: u8,
4634}
4635impl ACTUATOR_CONTROL_TARGET_DATA {
4636 pub const ENCODED_LEN: usize = 41usize;
4637 pub const DEFAULT: Self = Self {
4638 time_usec: 0_u64,
4639 controls: [0.0_f32; 8usize],
4640 group_mlx: 0_u8,
4641 };
4642 #[cfg(feature = "arbitrary")]
4643 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
4644 use arbitrary::{Arbitrary, Unstructured};
4645 let mut buf = [0u8; 1024];
4646 rng.fill_bytes(&mut buf);
4647 let mut unstructured = Unstructured::new(&buf);
4648 Self::arbitrary(&mut unstructured).unwrap_or_default()
4649 }
4650}
4651impl Default for ACTUATOR_CONTROL_TARGET_DATA {
4652 fn default() -> Self {
4653 Self::DEFAULT.clone()
4654 }
4655}
4656impl MessageData for ACTUATOR_CONTROL_TARGET_DATA {
4657 type Message = MavMessage;
4658 const ID: u32 = 140u32;
4659 const NAME: &'static str = "ACTUATOR_CONTROL_TARGET";
4660 const EXTRA_CRC: u8 = 181u8;
4661 const ENCODED_LEN: usize = 41usize;
4662 fn deser(
4663 _version: MavlinkVersion,
4664 __input: &[u8],
4665 ) -> Result<Self, ::mavlink_core::error::ParserError> {
4666 let avail_len = __input.len();
4667 let mut payload_buf = [0; Self::ENCODED_LEN];
4668 let mut buf = if avail_len < Self::ENCODED_LEN {
4669 payload_buf[0..avail_len].copy_from_slice(__input);
4670 Bytes::new(&payload_buf)
4671 } else {
4672 Bytes::new(__input)
4673 };
4674 let mut __struct = Self::default();
4675 __struct.time_usec = buf.get_u64_le();
4676 for v in &mut __struct.controls {
4677 let val = buf.get_f32_le();
4678 *v = val;
4679 }
4680 __struct.group_mlx = buf.get_u8();
4681 Ok(__struct)
4682 }
4683 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
4684 let mut __tmp = BytesMut::new(bytes);
4685 #[allow(clippy::absurd_extreme_comparisons)]
4686 #[allow(unused_comparisons)]
4687 if __tmp.remaining() < Self::ENCODED_LEN {
4688 panic!(
4689 "buffer is too small (need {} bytes, but got {})",
4690 Self::ENCODED_LEN,
4691 __tmp.remaining(),
4692 )
4693 }
4694 __tmp.put_u64_le(self.time_usec);
4695 for val in &self.controls {
4696 __tmp.put_f32_le(*val);
4697 }
4698 __tmp.put_u8(self.group_mlx);
4699 if matches!(version, MavlinkVersion::V2) {
4700 let len = __tmp.len();
4701 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
4702 } else {
4703 __tmp.len()
4704 }
4705 }
4706}
4707#[doc = "id: 375"]
4708#[doc = "The raw values of the actuator outputs (e.g. on Pixhawk, from MAIN, AUX ports). This message supersedes SERVO_OUTPUT_RAW."]
4709#[derive(Debug, Clone, PartialEq)]
4710#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4711#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4712pub struct ACTUATOR_OUTPUT_STATUS_DATA {
4713 #[doc = "Timestamp (since system boot)."]
4714 pub time_usec: u64,
4715 #[doc = "Active outputs"]
4716 pub active: u32,
4717 #[doc = "Servo / motor output array values. Zero values indicate unused channels."]
4718 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
4719 pub actuator: [f32; 32],
4720}
4721impl ACTUATOR_OUTPUT_STATUS_DATA {
4722 pub const ENCODED_LEN: usize = 140usize;
4723 pub const DEFAULT: Self = Self {
4724 time_usec: 0_u64,
4725 active: 0_u32,
4726 actuator: [0.0_f32; 32usize],
4727 };
4728 #[cfg(feature = "arbitrary")]
4729 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
4730 use arbitrary::{Arbitrary, Unstructured};
4731 let mut buf = [0u8; 1024];
4732 rng.fill_bytes(&mut buf);
4733 let mut unstructured = Unstructured::new(&buf);
4734 Self::arbitrary(&mut unstructured).unwrap_or_default()
4735 }
4736}
4737impl Default for ACTUATOR_OUTPUT_STATUS_DATA {
4738 fn default() -> Self {
4739 Self::DEFAULT.clone()
4740 }
4741}
4742impl MessageData for ACTUATOR_OUTPUT_STATUS_DATA {
4743 type Message = MavMessage;
4744 const ID: u32 = 375u32;
4745 const NAME: &'static str = "ACTUATOR_OUTPUT_STATUS";
4746 const EXTRA_CRC: u8 = 251u8;
4747 const ENCODED_LEN: usize = 140usize;
4748 fn deser(
4749 _version: MavlinkVersion,
4750 __input: &[u8],
4751 ) -> Result<Self, ::mavlink_core::error::ParserError> {
4752 let avail_len = __input.len();
4753 let mut payload_buf = [0; Self::ENCODED_LEN];
4754 let mut buf = if avail_len < Self::ENCODED_LEN {
4755 payload_buf[0..avail_len].copy_from_slice(__input);
4756 Bytes::new(&payload_buf)
4757 } else {
4758 Bytes::new(__input)
4759 };
4760 let mut __struct = Self::default();
4761 __struct.time_usec = buf.get_u64_le();
4762 __struct.active = buf.get_u32_le();
4763 for v in &mut __struct.actuator {
4764 let val = buf.get_f32_le();
4765 *v = val;
4766 }
4767 Ok(__struct)
4768 }
4769 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
4770 let mut __tmp = BytesMut::new(bytes);
4771 #[allow(clippy::absurd_extreme_comparisons)]
4772 #[allow(unused_comparisons)]
4773 if __tmp.remaining() < Self::ENCODED_LEN {
4774 panic!(
4775 "buffer is too small (need {} bytes, but got {})",
4776 Self::ENCODED_LEN,
4777 __tmp.remaining(),
4778 )
4779 }
4780 __tmp.put_u64_le(self.time_usec);
4781 __tmp.put_u32_le(self.active);
4782 for val in &self.actuator {
4783 __tmp.put_f32_le(*val);
4784 }
4785 if matches!(version, MavlinkVersion::V2) {
4786 let len = __tmp.len();
4787 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
4788 } else {
4789 __tmp.len()
4790 }
4791 }
4792}
4793#[doc = "id: 246"]
4794#[doc = "The location and information of an ADSB vehicle."]
4795#[derive(Debug, Clone, PartialEq)]
4796#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4797#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4798pub struct ADSB_VEHICLE_DATA {
4799 #[doc = "ICAO address"]
4800 pub ICAO_address: u32,
4801 #[doc = "Latitude"]
4802 pub lat: i32,
4803 #[doc = "Longitude"]
4804 pub lon: i32,
4805 #[doc = "Altitude(ASL)"]
4806 pub altitude: i32,
4807 #[doc = "Course over ground"]
4808 pub heading: u16,
4809 #[doc = "The horizontal velocity"]
4810 pub hor_velocity: u16,
4811 #[doc = "The vertical velocity. Positive is up"]
4812 pub ver_velocity: i16,
4813 #[doc = "Bitmap to indicate various statuses including valid data fields"]
4814 pub flags: AdsbFlags,
4815 #[doc = "Squawk code. Note that the code is in decimal: e.g. 7700 (general emergency) is encoded as binary 0b0001_1110_0001_0100, not(!) as 0b0000_111_111_000_000"]
4816 pub squawk: u16,
4817 #[doc = "ADSB altitude type."]
4818 pub altitude_type: AdsbAltitudeType,
4819 #[doc = "The callsign, 8+null"]
4820 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
4821 pub callsign: [u8; 9],
4822 #[doc = "ADSB emitter type."]
4823 pub emitter_type: AdsbEmitterType,
4824 #[doc = "Time since last communication in seconds"]
4825 pub tslc: u8,
4826}
4827impl ADSB_VEHICLE_DATA {
4828 pub const ENCODED_LEN: usize = 38usize;
4829 pub const DEFAULT: Self = Self {
4830 ICAO_address: 0_u32,
4831 lat: 0_i32,
4832 lon: 0_i32,
4833 altitude: 0_i32,
4834 heading: 0_u16,
4835 hor_velocity: 0_u16,
4836 ver_velocity: 0_i16,
4837 flags: AdsbFlags::DEFAULT,
4838 squawk: 0_u16,
4839 altitude_type: AdsbAltitudeType::DEFAULT,
4840 callsign: [0_u8; 9usize],
4841 emitter_type: AdsbEmitterType::DEFAULT,
4842 tslc: 0_u8,
4843 };
4844 #[cfg(feature = "arbitrary")]
4845 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
4846 use arbitrary::{Arbitrary, Unstructured};
4847 let mut buf = [0u8; 1024];
4848 rng.fill_bytes(&mut buf);
4849 let mut unstructured = Unstructured::new(&buf);
4850 Self::arbitrary(&mut unstructured).unwrap_or_default()
4851 }
4852}
4853impl Default for ADSB_VEHICLE_DATA {
4854 fn default() -> Self {
4855 Self::DEFAULT.clone()
4856 }
4857}
4858impl MessageData for ADSB_VEHICLE_DATA {
4859 type Message = MavMessage;
4860 const ID: u32 = 246u32;
4861 const NAME: &'static str = "ADSB_VEHICLE";
4862 const EXTRA_CRC: u8 = 184u8;
4863 const ENCODED_LEN: usize = 38usize;
4864 fn deser(
4865 _version: MavlinkVersion,
4866 __input: &[u8],
4867 ) -> Result<Self, ::mavlink_core::error::ParserError> {
4868 let avail_len = __input.len();
4869 let mut payload_buf = [0; Self::ENCODED_LEN];
4870 let mut buf = if avail_len < Self::ENCODED_LEN {
4871 payload_buf[0..avail_len].copy_from_slice(__input);
4872 Bytes::new(&payload_buf)
4873 } else {
4874 Bytes::new(__input)
4875 };
4876 let mut __struct = Self::default();
4877 __struct.ICAO_address = buf.get_u32_le();
4878 __struct.lat = buf.get_i32_le();
4879 __struct.lon = buf.get_i32_le();
4880 __struct.altitude = buf.get_i32_le();
4881 __struct.heading = buf.get_u16_le();
4882 __struct.hor_velocity = buf.get_u16_le();
4883 __struct.ver_velocity = buf.get_i16_le();
4884 let tmp = buf.get_u16_le();
4885 __struct.flags = AdsbFlags::from_bits(tmp & AdsbFlags::all().bits()).ok_or(
4886 ::mavlink_core::error::ParserError::InvalidFlag {
4887 flag_type: "AdsbFlags",
4888 value: tmp as u32,
4889 },
4890 )?;
4891 __struct.squawk = buf.get_u16_le();
4892 let tmp = buf.get_u8();
4893 __struct.altitude_type =
4894 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
4895 enum_type: "AdsbAltitudeType",
4896 value: tmp as u32,
4897 })?;
4898 for v in &mut __struct.callsign {
4899 let val = buf.get_u8();
4900 *v = val;
4901 }
4902 let tmp = buf.get_u8();
4903 __struct.emitter_type =
4904 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
4905 enum_type: "AdsbEmitterType",
4906 value: tmp as u32,
4907 })?;
4908 __struct.tslc = buf.get_u8();
4909 Ok(__struct)
4910 }
4911 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
4912 let mut __tmp = BytesMut::new(bytes);
4913 #[allow(clippy::absurd_extreme_comparisons)]
4914 #[allow(unused_comparisons)]
4915 if __tmp.remaining() < Self::ENCODED_LEN {
4916 panic!(
4917 "buffer is too small (need {} bytes, but got {})",
4918 Self::ENCODED_LEN,
4919 __tmp.remaining(),
4920 )
4921 }
4922 __tmp.put_u32_le(self.ICAO_address);
4923 __tmp.put_i32_le(self.lat);
4924 __tmp.put_i32_le(self.lon);
4925 __tmp.put_i32_le(self.altitude);
4926 __tmp.put_u16_le(self.heading);
4927 __tmp.put_u16_le(self.hor_velocity);
4928 __tmp.put_i16_le(self.ver_velocity);
4929 __tmp.put_u16_le(self.flags.bits());
4930 __tmp.put_u16_le(self.squawk);
4931 __tmp.put_u8(self.altitude_type as u8);
4932 for val in &self.callsign {
4933 __tmp.put_u8(*val);
4934 }
4935 __tmp.put_u8(self.emitter_type as u8);
4936 __tmp.put_u8(self.tslc);
4937 if matches!(version, MavlinkVersion::V2) {
4938 let len = __tmp.len();
4939 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
4940 } else {
4941 __tmp.len()
4942 }
4943 }
4944}
4945#[doc = "id: 301"]
4946#[doc = "The location and information of an AIS vessel."]
4947#[derive(Debug, Clone, PartialEq)]
4948#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4949#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4950pub struct AIS_VESSEL_DATA {
4951 #[doc = "Mobile Marine Service Identifier, 9 decimal digits"]
4952 pub MMSI: u32,
4953 #[doc = "Latitude"]
4954 pub lat: i32,
4955 #[doc = "Longitude"]
4956 pub lon: i32,
4957 #[doc = "Course over ground"]
4958 pub COG: u16,
4959 #[doc = "True heading"]
4960 pub heading: u16,
4961 #[doc = "Speed over ground"]
4962 pub velocity: u16,
4963 #[doc = "Distance from lat/lon location to bow"]
4964 pub dimension_bow: u16,
4965 #[doc = "Distance from lat/lon location to stern"]
4966 pub dimension_stern: u16,
4967 #[doc = "Time since last communication in seconds"]
4968 pub tslc: u16,
4969 #[doc = "Bitmask to indicate various statuses including valid data fields"]
4970 pub flags: AisFlags,
4971 #[doc = "Turn rate"]
4972 pub turn_rate: i8,
4973 #[doc = "Navigational status"]
4974 pub navigational_status: AisNavStatus,
4975 #[doc = "Type of vessels"]
4976 pub mavtype: AisType,
4977 #[doc = "Distance from lat/lon location to port side"]
4978 pub dimension_port: u8,
4979 #[doc = "Distance from lat/lon location to starboard side"]
4980 pub dimension_starboard: u8,
4981 #[doc = "The vessel callsign"]
4982 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
4983 pub callsign: [u8; 7],
4984 #[doc = "The vessel name"]
4985 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
4986 pub name: [u8; 20],
4987}
4988impl AIS_VESSEL_DATA {
4989 pub const ENCODED_LEN: usize = 58usize;
4990 pub const DEFAULT: Self = Self {
4991 MMSI: 0_u32,
4992 lat: 0_i32,
4993 lon: 0_i32,
4994 COG: 0_u16,
4995 heading: 0_u16,
4996 velocity: 0_u16,
4997 dimension_bow: 0_u16,
4998 dimension_stern: 0_u16,
4999 tslc: 0_u16,
5000 flags: AisFlags::DEFAULT,
5001 turn_rate: 0_i8,
5002 navigational_status: AisNavStatus::DEFAULT,
5003 mavtype: AisType::DEFAULT,
5004 dimension_port: 0_u8,
5005 dimension_starboard: 0_u8,
5006 callsign: [0_u8; 7usize],
5007 name: [0_u8; 20usize],
5008 };
5009 #[cfg(feature = "arbitrary")]
5010 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5011 use arbitrary::{Arbitrary, Unstructured};
5012 let mut buf = [0u8; 1024];
5013 rng.fill_bytes(&mut buf);
5014 let mut unstructured = Unstructured::new(&buf);
5015 Self::arbitrary(&mut unstructured).unwrap_or_default()
5016 }
5017}
5018impl Default for AIS_VESSEL_DATA {
5019 fn default() -> Self {
5020 Self::DEFAULT.clone()
5021 }
5022}
5023impl MessageData for AIS_VESSEL_DATA {
5024 type Message = MavMessage;
5025 const ID: u32 = 301u32;
5026 const NAME: &'static str = "AIS_VESSEL";
5027 const EXTRA_CRC: u8 = 243u8;
5028 const ENCODED_LEN: usize = 58usize;
5029 fn deser(
5030 _version: MavlinkVersion,
5031 __input: &[u8],
5032 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5033 let avail_len = __input.len();
5034 let mut payload_buf = [0; Self::ENCODED_LEN];
5035 let mut buf = if avail_len < Self::ENCODED_LEN {
5036 payload_buf[0..avail_len].copy_from_slice(__input);
5037 Bytes::new(&payload_buf)
5038 } else {
5039 Bytes::new(__input)
5040 };
5041 let mut __struct = Self::default();
5042 __struct.MMSI = buf.get_u32_le();
5043 __struct.lat = buf.get_i32_le();
5044 __struct.lon = buf.get_i32_le();
5045 __struct.COG = buf.get_u16_le();
5046 __struct.heading = buf.get_u16_le();
5047 __struct.velocity = buf.get_u16_le();
5048 __struct.dimension_bow = buf.get_u16_le();
5049 __struct.dimension_stern = buf.get_u16_le();
5050 __struct.tslc = buf.get_u16_le();
5051 let tmp = buf.get_u16_le();
5052 __struct.flags = AisFlags::from_bits(tmp & AisFlags::all().bits()).ok_or(
5053 ::mavlink_core::error::ParserError::InvalidFlag {
5054 flag_type: "AisFlags",
5055 value: tmp as u32,
5056 },
5057 )?;
5058 __struct.turn_rate = buf.get_i8();
5059 let tmp = buf.get_u8();
5060 __struct.navigational_status =
5061 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
5062 enum_type: "AisNavStatus",
5063 value: tmp as u32,
5064 })?;
5065 let tmp = buf.get_u8();
5066 __struct.mavtype =
5067 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
5068 enum_type: "AisType",
5069 value: tmp as u32,
5070 })?;
5071 __struct.dimension_port = buf.get_u8();
5072 __struct.dimension_starboard = buf.get_u8();
5073 for v in &mut __struct.callsign {
5074 let val = buf.get_u8();
5075 *v = val;
5076 }
5077 for v in &mut __struct.name {
5078 let val = buf.get_u8();
5079 *v = val;
5080 }
5081 Ok(__struct)
5082 }
5083 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5084 let mut __tmp = BytesMut::new(bytes);
5085 #[allow(clippy::absurd_extreme_comparisons)]
5086 #[allow(unused_comparisons)]
5087 if __tmp.remaining() < Self::ENCODED_LEN {
5088 panic!(
5089 "buffer is too small (need {} bytes, but got {})",
5090 Self::ENCODED_LEN,
5091 __tmp.remaining(),
5092 )
5093 }
5094 __tmp.put_u32_le(self.MMSI);
5095 __tmp.put_i32_le(self.lat);
5096 __tmp.put_i32_le(self.lon);
5097 __tmp.put_u16_le(self.COG);
5098 __tmp.put_u16_le(self.heading);
5099 __tmp.put_u16_le(self.velocity);
5100 __tmp.put_u16_le(self.dimension_bow);
5101 __tmp.put_u16_le(self.dimension_stern);
5102 __tmp.put_u16_le(self.tslc);
5103 __tmp.put_u16_le(self.flags.bits());
5104 __tmp.put_i8(self.turn_rate);
5105 __tmp.put_u8(self.navigational_status as u8);
5106 __tmp.put_u8(self.mavtype as u8);
5107 __tmp.put_u8(self.dimension_port);
5108 __tmp.put_u8(self.dimension_starboard);
5109 for val in &self.callsign {
5110 __tmp.put_u8(*val);
5111 }
5112 for val in &self.name {
5113 __tmp.put_u8(*val);
5114 }
5115 if matches!(version, MavlinkVersion::V2) {
5116 let len = __tmp.len();
5117 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5118 } else {
5119 __tmp.len()
5120 }
5121 }
5122}
5123#[doc = "id: 141"]
5124#[doc = "The current system altitude."]
5125#[derive(Debug, Clone, PartialEq)]
5126#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5127#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5128pub struct ALTITUDE_DATA {
5129 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
5130 pub time_usec: u64,
5131 #[doc = "This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights."]
5132 pub altitude_monotonic: f32,
5133 #[doc = "This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude."]
5134 pub altitude_amsl: f32,
5135 #[doc = "This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive."]
5136 pub altitude_local: f32,
5137 #[doc = "This is the altitude above the home position. It resets on each change of the current home position."]
5138 pub altitude_relative: f32,
5139 #[doc = "This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown."]
5140 pub altitude_terrain: f32,
5141 #[doc = "This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available."]
5142 pub bottom_clearance: f32,
5143}
5144impl ALTITUDE_DATA {
5145 pub const ENCODED_LEN: usize = 32usize;
5146 pub const DEFAULT: Self = Self {
5147 time_usec: 0_u64,
5148 altitude_monotonic: 0.0_f32,
5149 altitude_amsl: 0.0_f32,
5150 altitude_local: 0.0_f32,
5151 altitude_relative: 0.0_f32,
5152 altitude_terrain: 0.0_f32,
5153 bottom_clearance: 0.0_f32,
5154 };
5155 #[cfg(feature = "arbitrary")]
5156 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5157 use arbitrary::{Arbitrary, Unstructured};
5158 let mut buf = [0u8; 1024];
5159 rng.fill_bytes(&mut buf);
5160 let mut unstructured = Unstructured::new(&buf);
5161 Self::arbitrary(&mut unstructured).unwrap_or_default()
5162 }
5163}
5164impl Default for ALTITUDE_DATA {
5165 fn default() -> Self {
5166 Self::DEFAULT.clone()
5167 }
5168}
5169impl MessageData for ALTITUDE_DATA {
5170 type Message = MavMessage;
5171 const ID: u32 = 141u32;
5172 const NAME: &'static str = "ALTITUDE";
5173 const EXTRA_CRC: u8 = 47u8;
5174 const ENCODED_LEN: usize = 32usize;
5175 fn deser(
5176 _version: MavlinkVersion,
5177 __input: &[u8],
5178 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5179 let avail_len = __input.len();
5180 let mut payload_buf = [0; Self::ENCODED_LEN];
5181 let mut buf = if avail_len < Self::ENCODED_LEN {
5182 payload_buf[0..avail_len].copy_from_slice(__input);
5183 Bytes::new(&payload_buf)
5184 } else {
5185 Bytes::new(__input)
5186 };
5187 let mut __struct = Self::default();
5188 __struct.time_usec = buf.get_u64_le();
5189 __struct.altitude_monotonic = buf.get_f32_le();
5190 __struct.altitude_amsl = buf.get_f32_le();
5191 __struct.altitude_local = buf.get_f32_le();
5192 __struct.altitude_relative = buf.get_f32_le();
5193 __struct.altitude_terrain = buf.get_f32_le();
5194 __struct.bottom_clearance = buf.get_f32_le();
5195 Ok(__struct)
5196 }
5197 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5198 let mut __tmp = BytesMut::new(bytes);
5199 #[allow(clippy::absurd_extreme_comparisons)]
5200 #[allow(unused_comparisons)]
5201 if __tmp.remaining() < Self::ENCODED_LEN {
5202 panic!(
5203 "buffer is too small (need {} bytes, but got {})",
5204 Self::ENCODED_LEN,
5205 __tmp.remaining(),
5206 )
5207 }
5208 __tmp.put_u64_le(self.time_usec);
5209 __tmp.put_f32_le(self.altitude_monotonic);
5210 __tmp.put_f32_le(self.altitude_amsl);
5211 __tmp.put_f32_le(self.altitude_local);
5212 __tmp.put_f32_le(self.altitude_relative);
5213 __tmp.put_f32_le(self.altitude_terrain);
5214 __tmp.put_f32_le(self.bottom_clearance);
5215 if matches!(version, MavlinkVersion::V2) {
5216 let len = __tmp.len();
5217 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5218 } else {
5219 __tmp.len()
5220 }
5221 }
5222}
5223#[doc = "id: 30"]
5224#[doc = "The attitude in the aeronautical frame (right-handed, Z-down, Y-right, X-front, ZYX, intrinsic)."]
5225#[derive(Debug, Clone, PartialEq)]
5226#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5227#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5228pub struct ATTITUDE_DATA {
5229 #[doc = "Timestamp (time since system boot)."]
5230 pub time_boot_ms: u32,
5231 #[doc = "Roll angle (-pi..+pi)"]
5232 pub roll: f32,
5233 #[doc = "Pitch angle (-pi..+pi)"]
5234 pub pitch: f32,
5235 #[doc = "Yaw angle (-pi..+pi)"]
5236 pub yaw: f32,
5237 #[doc = "Roll angular speed"]
5238 pub rollspeed: f32,
5239 #[doc = "Pitch angular speed"]
5240 pub pitchspeed: f32,
5241 #[doc = "Yaw angular speed"]
5242 pub yawspeed: f32,
5243}
5244impl ATTITUDE_DATA {
5245 pub const ENCODED_LEN: usize = 28usize;
5246 pub const DEFAULT: Self = Self {
5247 time_boot_ms: 0_u32,
5248 roll: 0.0_f32,
5249 pitch: 0.0_f32,
5250 yaw: 0.0_f32,
5251 rollspeed: 0.0_f32,
5252 pitchspeed: 0.0_f32,
5253 yawspeed: 0.0_f32,
5254 };
5255 #[cfg(feature = "arbitrary")]
5256 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5257 use arbitrary::{Arbitrary, Unstructured};
5258 let mut buf = [0u8; 1024];
5259 rng.fill_bytes(&mut buf);
5260 let mut unstructured = Unstructured::new(&buf);
5261 Self::arbitrary(&mut unstructured).unwrap_or_default()
5262 }
5263}
5264impl Default for ATTITUDE_DATA {
5265 fn default() -> Self {
5266 Self::DEFAULT.clone()
5267 }
5268}
5269impl MessageData for ATTITUDE_DATA {
5270 type Message = MavMessage;
5271 const ID: u32 = 30u32;
5272 const NAME: &'static str = "ATTITUDE";
5273 const EXTRA_CRC: u8 = 39u8;
5274 const ENCODED_LEN: usize = 28usize;
5275 fn deser(
5276 _version: MavlinkVersion,
5277 __input: &[u8],
5278 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5279 let avail_len = __input.len();
5280 let mut payload_buf = [0; Self::ENCODED_LEN];
5281 let mut buf = if avail_len < Self::ENCODED_LEN {
5282 payload_buf[0..avail_len].copy_from_slice(__input);
5283 Bytes::new(&payload_buf)
5284 } else {
5285 Bytes::new(__input)
5286 };
5287 let mut __struct = Self::default();
5288 __struct.time_boot_ms = buf.get_u32_le();
5289 __struct.roll = buf.get_f32_le();
5290 __struct.pitch = buf.get_f32_le();
5291 __struct.yaw = buf.get_f32_le();
5292 __struct.rollspeed = buf.get_f32_le();
5293 __struct.pitchspeed = buf.get_f32_le();
5294 __struct.yawspeed = buf.get_f32_le();
5295 Ok(__struct)
5296 }
5297 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5298 let mut __tmp = BytesMut::new(bytes);
5299 #[allow(clippy::absurd_extreme_comparisons)]
5300 #[allow(unused_comparisons)]
5301 if __tmp.remaining() < Self::ENCODED_LEN {
5302 panic!(
5303 "buffer is too small (need {} bytes, but got {})",
5304 Self::ENCODED_LEN,
5305 __tmp.remaining(),
5306 )
5307 }
5308 __tmp.put_u32_le(self.time_boot_ms);
5309 __tmp.put_f32_le(self.roll);
5310 __tmp.put_f32_le(self.pitch);
5311 __tmp.put_f32_le(self.yaw);
5312 __tmp.put_f32_le(self.rollspeed);
5313 __tmp.put_f32_le(self.pitchspeed);
5314 __tmp.put_f32_le(self.yawspeed);
5315 if matches!(version, MavlinkVersion::V2) {
5316 let len = __tmp.len();
5317 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5318 } else {
5319 __tmp.len()
5320 }
5321 }
5322}
5323#[doc = "id: 31"]
5324#[doc = "The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0)."]
5325#[derive(Debug, Clone, PartialEq)]
5326#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5327#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5328pub struct ATTITUDE_QUATERNION_DATA {
5329 #[doc = "Timestamp (time since system boot)."]
5330 pub time_boot_ms: u32,
5331 #[doc = "Quaternion component 1, w (1 in null-rotation)"]
5332 pub q1: f32,
5333 #[doc = "Quaternion component 2, x (0 in null-rotation)"]
5334 pub q2: f32,
5335 #[doc = "Quaternion component 3, y (0 in null-rotation)"]
5336 pub q3: f32,
5337 #[doc = "Quaternion component 4, z (0 in null-rotation)"]
5338 pub q4: f32,
5339 #[doc = "Roll angular speed"]
5340 pub rollspeed: f32,
5341 #[doc = "Pitch angular speed"]
5342 pub pitchspeed: f32,
5343 #[doc = "Yaw angular speed"]
5344 pub yawspeed: f32,
5345 #[doc = "Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode."]
5346 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
5347 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5348 pub repr_offset_q: [f32; 4],
5349}
5350impl ATTITUDE_QUATERNION_DATA {
5351 pub const ENCODED_LEN: usize = 48usize;
5352 pub const DEFAULT: Self = Self {
5353 time_boot_ms: 0_u32,
5354 q1: 0.0_f32,
5355 q2: 0.0_f32,
5356 q3: 0.0_f32,
5357 q4: 0.0_f32,
5358 rollspeed: 0.0_f32,
5359 pitchspeed: 0.0_f32,
5360 yawspeed: 0.0_f32,
5361 repr_offset_q: [0.0_f32; 4usize],
5362 };
5363 #[cfg(feature = "arbitrary")]
5364 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5365 use arbitrary::{Arbitrary, Unstructured};
5366 let mut buf = [0u8; 1024];
5367 rng.fill_bytes(&mut buf);
5368 let mut unstructured = Unstructured::new(&buf);
5369 Self::arbitrary(&mut unstructured).unwrap_or_default()
5370 }
5371}
5372impl Default for ATTITUDE_QUATERNION_DATA {
5373 fn default() -> Self {
5374 Self::DEFAULT.clone()
5375 }
5376}
5377impl MessageData for ATTITUDE_QUATERNION_DATA {
5378 type Message = MavMessage;
5379 const ID: u32 = 31u32;
5380 const NAME: &'static str = "ATTITUDE_QUATERNION";
5381 const EXTRA_CRC: u8 = 246u8;
5382 const ENCODED_LEN: usize = 48usize;
5383 fn deser(
5384 _version: MavlinkVersion,
5385 __input: &[u8],
5386 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5387 let avail_len = __input.len();
5388 let mut payload_buf = [0; Self::ENCODED_LEN];
5389 let mut buf = if avail_len < Self::ENCODED_LEN {
5390 payload_buf[0..avail_len].copy_from_slice(__input);
5391 Bytes::new(&payload_buf)
5392 } else {
5393 Bytes::new(__input)
5394 };
5395 let mut __struct = Self::default();
5396 __struct.time_boot_ms = buf.get_u32_le();
5397 __struct.q1 = buf.get_f32_le();
5398 __struct.q2 = buf.get_f32_le();
5399 __struct.q3 = buf.get_f32_le();
5400 __struct.q4 = buf.get_f32_le();
5401 __struct.rollspeed = buf.get_f32_le();
5402 __struct.pitchspeed = buf.get_f32_le();
5403 __struct.yawspeed = buf.get_f32_le();
5404 for v in &mut __struct.repr_offset_q {
5405 let val = buf.get_f32_le();
5406 *v = val;
5407 }
5408 Ok(__struct)
5409 }
5410 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5411 let mut __tmp = BytesMut::new(bytes);
5412 #[allow(clippy::absurd_extreme_comparisons)]
5413 #[allow(unused_comparisons)]
5414 if __tmp.remaining() < Self::ENCODED_LEN {
5415 panic!(
5416 "buffer is too small (need {} bytes, but got {})",
5417 Self::ENCODED_LEN,
5418 __tmp.remaining(),
5419 )
5420 }
5421 __tmp.put_u32_le(self.time_boot_ms);
5422 __tmp.put_f32_le(self.q1);
5423 __tmp.put_f32_le(self.q2);
5424 __tmp.put_f32_le(self.q3);
5425 __tmp.put_f32_le(self.q4);
5426 __tmp.put_f32_le(self.rollspeed);
5427 __tmp.put_f32_le(self.pitchspeed);
5428 __tmp.put_f32_le(self.yawspeed);
5429 for val in &self.repr_offset_q {
5430 __tmp.put_f32_le(*val);
5431 }
5432 if matches!(version, MavlinkVersion::V2) {
5433 let len = __tmp.len();
5434 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5435 } else {
5436 __tmp.len()
5437 }
5438 }
5439}
5440#[doc = "id: 61"]
5441#[doc = "The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0)."]
5442#[derive(Debug, Clone, PartialEq)]
5443#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5444#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5445pub struct ATTITUDE_QUATERNION_COV_DATA {
5446 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
5447 pub time_usec: u64,
5448 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)"]
5449 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5450 pub q: [f32; 4],
5451 #[doc = "Roll angular speed"]
5452 pub rollspeed: f32,
5453 #[doc = "Pitch angular speed"]
5454 pub pitchspeed: f32,
5455 #[doc = "Yaw angular speed"]
5456 pub yawspeed: f32,
5457 #[doc = "Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array."]
5458 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5459 pub covariance: [f32; 9],
5460}
5461impl ATTITUDE_QUATERNION_COV_DATA {
5462 pub const ENCODED_LEN: usize = 72usize;
5463 pub const DEFAULT: Self = Self {
5464 time_usec: 0_u64,
5465 q: [0.0_f32; 4usize],
5466 rollspeed: 0.0_f32,
5467 pitchspeed: 0.0_f32,
5468 yawspeed: 0.0_f32,
5469 covariance: [0.0_f32; 9usize],
5470 };
5471 #[cfg(feature = "arbitrary")]
5472 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5473 use arbitrary::{Arbitrary, Unstructured};
5474 let mut buf = [0u8; 1024];
5475 rng.fill_bytes(&mut buf);
5476 let mut unstructured = Unstructured::new(&buf);
5477 Self::arbitrary(&mut unstructured).unwrap_or_default()
5478 }
5479}
5480impl Default for ATTITUDE_QUATERNION_COV_DATA {
5481 fn default() -> Self {
5482 Self::DEFAULT.clone()
5483 }
5484}
5485impl MessageData for ATTITUDE_QUATERNION_COV_DATA {
5486 type Message = MavMessage;
5487 const ID: u32 = 61u32;
5488 const NAME: &'static str = "ATTITUDE_QUATERNION_COV";
5489 const EXTRA_CRC: u8 = 167u8;
5490 const ENCODED_LEN: usize = 72usize;
5491 fn deser(
5492 _version: MavlinkVersion,
5493 __input: &[u8],
5494 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5495 let avail_len = __input.len();
5496 let mut payload_buf = [0; Self::ENCODED_LEN];
5497 let mut buf = if avail_len < Self::ENCODED_LEN {
5498 payload_buf[0..avail_len].copy_from_slice(__input);
5499 Bytes::new(&payload_buf)
5500 } else {
5501 Bytes::new(__input)
5502 };
5503 let mut __struct = Self::default();
5504 __struct.time_usec = buf.get_u64_le();
5505 for v in &mut __struct.q {
5506 let val = buf.get_f32_le();
5507 *v = val;
5508 }
5509 __struct.rollspeed = buf.get_f32_le();
5510 __struct.pitchspeed = buf.get_f32_le();
5511 __struct.yawspeed = buf.get_f32_le();
5512 for v in &mut __struct.covariance {
5513 let val = buf.get_f32_le();
5514 *v = val;
5515 }
5516 Ok(__struct)
5517 }
5518 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5519 let mut __tmp = BytesMut::new(bytes);
5520 #[allow(clippy::absurd_extreme_comparisons)]
5521 #[allow(unused_comparisons)]
5522 if __tmp.remaining() < Self::ENCODED_LEN {
5523 panic!(
5524 "buffer is too small (need {} bytes, but got {})",
5525 Self::ENCODED_LEN,
5526 __tmp.remaining(),
5527 )
5528 }
5529 __tmp.put_u64_le(self.time_usec);
5530 for val in &self.q {
5531 __tmp.put_f32_le(*val);
5532 }
5533 __tmp.put_f32_le(self.rollspeed);
5534 __tmp.put_f32_le(self.pitchspeed);
5535 __tmp.put_f32_le(self.yawspeed);
5536 for val in &self.covariance {
5537 __tmp.put_f32_le(*val);
5538 }
5539 if matches!(version, MavlinkVersion::V2) {
5540 let len = __tmp.len();
5541 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5542 } else {
5543 __tmp.len()
5544 }
5545 }
5546}
5547#[doc = "id: 83"]
5548#[doc = "Reports the current commanded attitude of the vehicle as specified by the autopilot. This should match the commands sent in a SET_ATTITUDE_TARGET message if the vehicle is being controlled this way."]
5549#[derive(Debug, Clone, PartialEq)]
5550#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5551#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5552pub struct ATTITUDE_TARGET_DATA {
5553 #[doc = "Timestamp (time since system boot)."]
5554 pub time_boot_ms: u32,
5555 #[doc = "Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
5556 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5557 pub q: [f32; 4],
5558 #[doc = "Body roll rate"]
5559 pub body_roll_rate: f32,
5560 #[doc = "Body pitch rate"]
5561 pub body_pitch_rate: f32,
5562 #[doc = "Body yaw rate"]
5563 pub body_yaw_rate: f32,
5564 #[doc = "Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)"]
5565 pub thrust: f32,
5566 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
5567 pub type_mask: AttitudeTargetTypemask,
5568}
5569impl ATTITUDE_TARGET_DATA {
5570 pub const ENCODED_LEN: usize = 37usize;
5571 pub const DEFAULT: Self = Self {
5572 time_boot_ms: 0_u32,
5573 q: [0.0_f32; 4usize],
5574 body_roll_rate: 0.0_f32,
5575 body_pitch_rate: 0.0_f32,
5576 body_yaw_rate: 0.0_f32,
5577 thrust: 0.0_f32,
5578 type_mask: AttitudeTargetTypemask::DEFAULT,
5579 };
5580 #[cfg(feature = "arbitrary")]
5581 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5582 use arbitrary::{Arbitrary, Unstructured};
5583 let mut buf = [0u8; 1024];
5584 rng.fill_bytes(&mut buf);
5585 let mut unstructured = Unstructured::new(&buf);
5586 Self::arbitrary(&mut unstructured).unwrap_or_default()
5587 }
5588}
5589impl Default for ATTITUDE_TARGET_DATA {
5590 fn default() -> Self {
5591 Self::DEFAULT.clone()
5592 }
5593}
5594impl MessageData for ATTITUDE_TARGET_DATA {
5595 type Message = MavMessage;
5596 const ID: u32 = 83u32;
5597 const NAME: &'static str = "ATTITUDE_TARGET";
5598 const EXTRA_CRC: u8 = 22u8;
5599 const ENCODED_LEN: usize = 37usize;
5600 fn deser(
5601 _version: MavlinkVersion,
5602 __input: &[u8],
5603 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5604 let avail_len = __input.len();
5605 let mut payload_buf = [0; Self::ENCODED_LEN];
5606 let mut buf = if avail_len < Self::ENCODED_LEN {
5607 payload_buf[0..avail_len].copy_from_slice(__input);
5608 Bytes::new(&payload_buf)
5609 } else {
5610 Bytes::new(__input)
5611 };
5612 let mut __struct = Self::default();
5613 __struct.time_boot_ms = buf.get_u32_le();
5614 for v in &mut __struct.q {
5615 let val = buf.get_f32_le();
5616 *v = val;
5617 }
5618 __struct.body_roll_rate = buf.get_f32_le();
5619 __struct.body_pitch_rate = buf.get_f32_le();
5620 __struct.body_yaw_rate = buf.get_f32_le();
5621 __struct.thrust = buf.get_f32_le();
5622 let tmp = buf.get_u8();
5623 __struct.type_mask = AttitudeTargetTypemask::from_bits(
5624 tmp & AttitudeTargetTypemask::all().bits(),
5625 )
5626 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
5627 flag_type: "AttitudeTargetTypemask",
5628 value: tmp as u32,
5629 })?;
5630 Ok(__struct)
5631 }
5632 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5633 let mut __tmp = BytesMut::new(bytes);
5634 #[allow(clippy::absurd_extreme_comparisons)]
5635 #[allow(unused_comparisons)]
5636 if __tmp.remaining() < Self::ENCODED_LEN {
5637 panic!(
5638 "buffer is too small (need {} bytes, but got {})",
5639 Self::ENCODED_LEN,
5640 __tmp.remaining(),
5641 )
5642 }
5643 __tmp.put_u32_le(self.time_boot_ms);
5644 for val in &self.q {
5645 __tmp.put_f32_le(*val);
5646 }
5647 __tmp.put_f32_le(self.body_roll_rate);
5648 __tmp.put_f32_le(self.body_pitch_rate);
5649 __tmp.put_f32_le(self.body_yaw_rate);
5650 __tmp.put_f32_le(self.thrust);
5651 __tmp.put_u8(self.type_mask.bits());
5652 if matches!(version, MavlinkVersion::V2) {
5653 let len = __tmp.len();
5654 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5655 } else {
5656 __tmp.len()
5657 }
5658 }
5659}
5660#[doc = "id: 138"]
5661#[doc = "Motion capture attitude and position."]
5662#[derive(Debug, Clone, PartialEq)]
5663#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5664#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5665pub struct ATT_POS_MOCAP_DATA {
5666 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
5667 pub time_usec: u64,
5668 #[doc = "Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
5669 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5670 pub q: [f32; 4],
5671 #[doc = "X position (NED)"]
5672 pub x: f32,
5673 #[doc = "Y position (NED)"]
5674 pub y: f32,
5675 #[doc = "Z position (NED)"]
5676 pub z: f32,
5677 #[doc = "Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
5678 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
5679 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5680 pub covariance: [f32; 21],
5681}
5682impl ATT_POS_MOCAP_DATA {
5683 pub const ENCODED_LEN: usize = 120usize;
5684 pub const DEFAULT: Self = Self {
5685 time_usec: 0_u64,
5686 q: [0.0_f32; 4usize],
5687 x: 0.0_f32,
5688 y: 0.0_f32,
5689 z: 0.0_f32,
5690 covariance: [0.0_f32; 21usize],
5691 };
5692 #[cfg(feature = "arbitrary")]
5693 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5694 use arbitrary::{Arbitrary, Unstructured};
5695 let mut buf = [0u8; 1024];
5696 rng.fill_bytes(&mut buf);
5697 let mut unstructured = Unstructured::new(&buf);
5698 Self::arbitrary(&mut unstructured).unwrap_or_default()
5699 }
5700}
5701impl Default for ATT_POS_MOCAP_DATA {
5702 fn default() -> Self {
5703 Self::DEFAULT.clone()
5704 }
5705}
5706impl MessageData for ATT_POS_MOCAP_DATA {
5707 type Message = MavMessage;
5708 const ID: u32 = 138u32;
5709 const NAME: &'static str = "ATT_POS_MOCAP";
5710 const EXTRA_CRC: u8 = 109u8;
5711 const ENCODED_LEN: usize = 120usize;
5712 fn deser(
5713 _version: MavlinkVersion,
5714 __input: &[u8],
5715 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5716 let avail_len = __input.len();
5717 let mut payload_buf = [0; Self::ENCODED_LEN];
5718 let mut buf = if avail_len < Self::ENCODED_LEN {
5719 payload_buf[0..avail_len].copy_from_slice(__input);
5720 Bytes::new(&payload_buf)
5721 } else {
5722 Bytes::new(__input)
5723 };
5724 let mut __struct = Self::default();
5725 __struct.time_usec = buf.get_u64_le();
5726 for v in &mut __struct.q {
5727 let val = buf.get_f32_le();
5728 *v = val;
5729 }
5730 __struct.x = buf.get_f32_le();
5731 __struct.y = buf.get_f32_le();
5732 __struct.z = buf.get_f32_le();
5733 for v in &mut __struct.covariance {
5734 let val = buf.get_f32_le();
5735 *v = val;
5736 }
5737 Ok(__struct)
5738 }
5739 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5740 let mut __tmp = BytesMut::new(bytes);
5741 #[allow(clippy::absurd_extreme_comparisons)]
5742 #[allow(unused_comparisons)]
5743 if __tmp.remaining() < Self::ENCODED_LEN {
5744 panic!(
5745 "buffer is too small (need {} bytes, but got {})",
5746 Self::ENCODED_LEN,
5747 __tmp.remaining(),
5748 )
5749 }
5750 __tmp.put_u64_le(self.time_usec);
5751 for val in &self.q {
5752 __tmp.put_f32_le(*val);
5753 }
5754 __tmp.put_f32_le(self.x);
5755 __tmp.put_f32_le(self.y);
5756 __tmp.put_f32_le(self.z);
5757 for val in &self.covariance {
5758 __tmp.put_f32_le(*val);
5759 }
5760 if matches!(version, MavlinkVersion::V2) {
5761 let len = __tmp.len();
5762 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5763 } else {
5764 __tmp.len()
5765 }
5766 }
5767}
5768#[doc = "id: 7"]
5769#[doc = "Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety."]
5770#[derive(Debug, Clone, PartialEq)]
5771#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5772#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5773pub struct AUTH_KEY_DATA {
5774 #[doc = "key"]
5775 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5776 pub key: [u8; 32],
5777}
5778impl AUTH_KEY_DATA {
5779 pub const ENCODED_LEN: usize = 32usize;
5780 pub const DEFAULT: Self = Self {
5781 key: [0_u8; 32usize],
5782 };
5783 #[cfg(feature = "arbitrary")]
5784 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5785 use arbitrary::{Arbitrary, Unstructured};
5786 let mut buf = [0u8; 1024];
5787 rng.fill_bytes(&mut buf);
5788 let mut unstructured = Unstructured::new(&buf);
5789 Self::arbitrary(&mut unstructured).unwrap_or_default()
5790 }
5791}
5792impl Default for AUTH_KEY_DATA {
5793 fn default() -> Self {
5794 Self::DEFAULT.clone()
5795 }
5796}
5797impl MessageData for AUTH_KEY_DATA {
5798 type Message = MavMessage;
5799 const ID: u32 = 7u32;
5800 const NAME: &'static str = "AUTH_KEY";
5801 const EXTRA_CRC: u8 = 119u8;
5802 const ENCODED_LEN: usize = 32usize;
5803 fn deser(
5804 _version: MavlinkVersion,
5805 __input: &[u8],
5806 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5807 let avail_len = __input.len();
5808 let mut payload_buf = [0; Self::ENCODED_LEN];
5809 let mut buf = if avail_len < Self::ENCODED_LEN {
5810 payload_buf[0..avail_len].copy_from_slice(__input);
5811 Bytes::new(&payload_buf)
5812 } else {
5813 Bytes::new(__input)
5814 };
5815 let mut __struct = Self::default();
5816 for v in &mut __struct.key {
5817 let val = buf.get_u8();
5818 *v = val;
5819 }
5820 Ok(__struct)
5821 }
5822 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5823 let mut __tmp = BytesMut::new(bytes);
5824 #[allow(clippy::absurd_extreme_comparisons)]
5825 #[allow(unused_comparisons)]
5826 if __tmp.remaining() < Self::ENCODED_LEN {
5827 panic!(
5828 "buffer is too small (need {} bytes, but got {})",
5829 Self::ENCODED_LEN,
5830 __tmp.remaining(),
5831 )
5832 }
5833 for val in &self.key {
5834 __tmp.put_u8(*val);
5835 }
5836 if matches!(version, MavlinkVersion::V2) {
5837 let len = __tmp.len();
5838 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5839 } else {
5840 __tmp.len()
5841 }
5842 }
5843}
5844#[doc = "id: 286"]
5845#[doc = "Low level message containing autopilot state relevant for a gimbal device. This message is to be sent from the autopilot to the gimbal device component. The data of this message are for the gimbal device's estimator corrections, in particular horizon compensation, as well as indicates autopilot control intentions, e.g. feed forward angular control in the z-axis."]
5846#[derive(Debug, Clone, PartialEq)]
5847#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5848#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5849pub struct AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
5850 #[doc = "Timestamp (time since system boot)."]
5851 pub time_boot_us: u64,
5852 #[doc = "Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention)."]
5853 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5854 pub q: [f32; 4],
5855 #[doc = "Estimated delay of the attitude data. 0 if unknown."]
5856 pub q_estimated_delay_us: u32,
5857 #[doc = "X Speed in NED (North, East, Down). NAN if unknown."]
5858 pub vx: f32,
5859 #[doc = "Y Speed in NED (North, East, Down). NAN if unknown."]
5860 pub vy: f32,
5861 #[doc = "Z Speed in NED (North, East, Down). NAN if unknown."]
5862 pub vz: f32,
5863 #[doc = "Estimated delay of the speed data. 0 if unknown."]
5864 pub v_estimated_delay_us: u32,
5865 #[doc = "Feed forward Z component of angular velocity (positive: yawing to the right). NaN to be ignored. This is to indicate if the autopilot is actively yawing."]
5866 pub feed_forward_angular_velocity_z: f32,
5867 #[doc = "Bitmap indicating which estimator outputs are valid."]
5868 pub estimator_status: EstimatorStatusFlags,
5869 #[doc = "System ID"]
5870 pub target_system: u8,
5871 #[doc = "Component ID"]
5872 pub target_component: u8,
5873 #[doc = "The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown."]
5874 pub landed_state: MavLandedState,
5875 #[doc = "Z component of angular velocity in NED (North, East, Down). NaN if unknown."]
5876 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
5877 pub angular_velocity_z: f32,
5878}
5879impl AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
5880 pub const ENCODED_LEN: usize = 57usize;
5881 pub const DEFAULT: Self = Self {
5882 time_boot_us: 0_u64,
5883 q: [0.0_f32; 4usize],
5884 q_estimated_delay_us: 0_u32,
5885 vx: 0.0_f32,
5886 vy: 0.0_f32,
5887 vz: 0.0_f32,
5888 v_estimated_delay_us: 0_u32,
5889 feed_forward_angular_velocity_z: 0.0_f32,
5890 estimator_status: EstimatorStatusFlags::DEFAULT,
5891 target_system: 0_u8,
5892 target_component: 0_u8,
5893 landed_state: MavLandedState::DEFAULT,
5894 angular_velocity_z: 0.0_f32,
5895 };
5896 #[cfg(feature = "arbitrary")]
5897 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5898 use arbitrary::{Arbitrary, Unstructured};
5899 let mut buf = [0u8; 1024];
5900 rng.fill_bytes(&mut buf);
5901 let mut unstructured = Unstructured::new(&buf);
5902 Self::arbitrary(&mut unstructured).unwrap_or_default()
5903 }
5904}
5905impl Default for AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
5906 fn default() -> Self {
5907 Self::DEFAULT.clone()
5908 }
5909}
5910impl MessageData for AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
5911 type Message = MavMessage;
5912 const ID: u32 = 286u32;
5913 const NAME: &'static str = "AUTOPILOT_STATE_FOR_GIMBAL_DEVICE";
5914 const EXTRA_CRC: u8 = 210u8;
5915 const ENCODED_LEN: usize = 57usize;
5916 fn deser(
5917 _version: MavlinkVersion,
5918 __input: &[u8],
5919 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5920 let avail_len = __input.len();
5921 let mut payload_buf = [0; Self::ENCODED_LEN];
5922 let mut buf = if avail_len < Self::ENCODED_LEN {
5923 payload_buf[0..avail_len].copy_from_slice(__input);
5924 Bytes::new(&payload_buf)
5925 } else {
5926 Bytes::new(__input)
5927 };
5928 let mut __struct = Self::default();
5929 __struct.time_boot_us = buf.get_u64_le();
5930 for v in &mut __struct.q {
5931 let val = buf.get_f32_le();
5932 *v = val;
5933 }
5934 __struct.q_estimated_delay_us = buf.get_u32_le();
5935 __struct.vx = buf.get_f32_le();
5936 __struct.vy = buf.get_f32_le();
5937 __struct.vz = buf.get_f32_le();
5938 __struct.v_estimated_delay_us = buf.get_u32_le();
5939 __struct.feed_forward_angular_velocity_z = buf.get_f32_le();
5940 let tmp = buf.get_u16_le();
5941 __struct.estimator_status = EstimatorStatusFlags::from_bits(
5942 tmp & EstimatorStatusFlags::all().bits(),
5943 )
5944 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
5945 flag_type: "EstimatorStatusFlags",
5946 value: tmp as u32,
5947 })?;
5948 __struct.target_system = buf.get_u8();
5949 __struct.target_component = buf.get_u8();
5950 let tmp = buf.get_u8();
5951 __struct.landed_state =
5952 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
5953 enum_type: "MavLandedState",
5954 value: tmp as u32,
5955 })?;
5956 __struct.angular_velocity_z = buf.get_f32_le();
5957 Ok(__struct)
5958 }
5959 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5960 let mut __tmp = BytesMut::new(bytes);
5961 #[allow(clippy::absurd_extreme_comparisons)]
5962 #[allow(unused_comparisons)]
5963 if __tmp.remaining() < Self::ENCODED_LEN {
5964 panic!(
5965 "buffer is too small (need {} bytes, but got {})",
5966 Self::ENCODED_LEN,
5967 __tmp.remaining(),
5968 )
5969 }
5970 __tmp.put_u64_le(self.time_boot_us);
5971 for val in &self.q {
5972 __tmp.put_f32_le(*val);
5973 }
5974 __tmp.put_u32_le(self.q_estimated_delay_us);
5975 __tmp.put_f32_le(self.vx);
5976 __tmp.put_f32_le(self.vy);
5977 __tmp.put_f32_le(self.vz);
5978 __tmp.put_u32_le(self.v_estimated_delay_us);
5979 __tmp.put_f32_le(self.feed_forward_angular_velocity_z);
5980 __tmp.put_u16_le(self.estimator_status.bits());
5981 __tmp.put_u8(self.target_system);
5982 __tmp.put_u8(self.target_component);
5983 __tmp.put_u8(self.landed_state as u8);
5984 __tmp.put_f32_le(self.angular_velocity_z);
5985 if matches!(version, MavlinkVersion::V2) {
5986 let len = __tmp.len();
5987 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5988 } else {
5989 __tmp.len()
5990 }
5991 }
5992}
5993#[doc = "id: 148"]
5994#[doc = "Version and capability of autopilot software. This should be emitted in response to a request with MAV_CMD_REQUEST_MESSAGE."]
5995#[derive(Debug, Clone, PartialEq)]
5996#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5997#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5998pub struct AUTOPILOT_VERSION_DATA {
5999 #[doc = "Bitmap of capabilities"]
6000 pub capabilities: MavProtocolCapability,
6001 #[doc = "UID if provided by hardware (see uid2)"]
6002 pub uid: u64,
6003 #[doc = "Firmware version number. The field must be encoded as 4 bytes, where each byte (shown from MSB to LSB) is part of a semantic version: (major) (minor) (patch) (FIRMWARE_VERSION_TYPE)."]
6004 pub flight_sw_version: u32,
6005 #[doc = "Middleware version number"]
6006 pub middleware_sw_version: u32,
6007 #[doc = "Operating system version number"]
6008 pub os_sw_version: u32,
6009 #[doc = "HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify <https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt>"]
6010 pub board_version: u32,
6011 #[doc = "ID of the board vendor"]
6012 pub vendor_id: u16,
6013 #[doc = "ID of the product"]
6014 pub product_id: u16,
6015 #[doc = "Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases."]
6016 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6017 pub flight_custom_version: [u8; 8],
6018 #[doc = "Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases."]
6019 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6020 pub middleware_custom_version: [u8; 8],
6021 #[doc = "Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases."]
6022 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6023 pub os_custom_version: [u8; 8],
6024 #[doc = "UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)"]
6025 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6026 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6027 pub uid2: [u8; 18],
6028}
6029impl AUTOPILOT_VERSION_DATA {
6030 pub const ENCODED_LEN: usize = 78usize;
6031 pub const DEFAULT: Self = Self {
6032 capabilities: MavProtocolCapability::DEFAULT,
6033 uid: 0_u64,
6034 flight_sw_version: 0_u32,
6035 middleware_sw_version: 0_u32,
6036 os_sw_version: 0_u32,
6037 board_version: 0_u32,
6038 vendor_id: 0_u16,
6039 product_id: 0_u16,
6040 flight_custom_version: [0_u8; 8usize],
6041 middleware_custom_version: [0_u8; 8usize],
6042 os_custom_version: [0_u8; 8usize],
6043 uid2: [0_u8; 18usize],
6044 };
6045 #[cfg(feature = "arbitrary")]
6046 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6047 use arbitrary::{Arbitrary, Unstructured};
6048 let mut buf = [0u8; 1024];
6049 rng.fill_bytes(&mut buf);
6050 let mut unstructured = Unstructured::new(&buf);
6051 Self::arbitrary(&mut unstructured).unwrap_or_default()
6052 }
6053}
6054impl Default for AUTOPILOT_VERSION_DATA {
6055 fn default() -> Self {
6056 Self::DEFAULT.clone()
6057 }
6058}
6059impl MessageData for AUTOPILOT_VERSION_DATA {
6060 type Message = MavMessage;
6061 const ID: u32 = 148u32;
6062 const NAME: &'static str = "AUTOPILOT_VERSION";
6063 const EXTRA_CRC: u8 = 178u8;
6064 const ENCODED_LEN: usize = 78usize;
6065 fn deser(
6066 _version: MavlinkVersion,
6067 __input: &[u8],
6068 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6069 let avail_len = __input.len();
6070 let mut payload_buf = [0; Self::ENCODED_LEN];
6071 let mut buf = if avail_len < Self::ENCODED_LEN {
6072 payload_buf[0..avail_len].copy_from_slice(__input);
6073 Bytes::new(&payload_buf)
6074 } else {
6075 Bytes::new(__input)
6076 };
6077 let mut __struct = Self::default();
6078 let tmp = buf.get_u64_le();
6079 __struct.capabilities = MavProtocolCapability::from_bits(
6080 tmp & MavProtocolCapability::all().bits(),
6081 )
6082 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
6083 flag_type: "MavProtocolCapability",
6084 value: tmp as u32,
6085 })?;
6086 __struct.uid = buf.get_u64_le();
6087 __struct.flight_sw_version = buf.get_u32_le();
6088 __struct.middleware_sw_version = buf.get_u32_le();
6089 __struct.os_sw_version = buf.get_u32_le();
6090 __struct.board_version = buf.get_u32_le();
6091 __struct.vendor_id = buf.get_u16_le();
6092 __struct.product_id = buf.get_u16_le();
6093 for v in &mut __struct.flight_custom_version {
6094 let val = buf.get_u8();
6095 *v = val;
6096 }
6097 for v in &mut __struct.middleware_custom_version {
6098 let val = buf.get_u8();
6099 *v = val;
6100 }
6101 for v in &mut __struct.os_custom_version {
6102 let val = buf.get_u8();
6103 *v = val;
6104 }
6105 for v in &mut __struct.uid2 {
6106 let val = buf.get_u8();
6107 *v = val;
6108 }
6109 Ok(__struct)
6110 }
6111 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6112 let mut __tmp = BytesMut::new(bytes);
6113 #[allow(clippy::absurd_extreme_comparisons)]
6114 #[allow(unused_comparisons)]
6115 if __tmp.remaining() < Self::ENCODED_LEN {
6116 panic!(
6117 "buffer is too small (need {} bytes, but got {})",
6118 Self::ENCODED_LEN,
6119 __tmp.remaining(),
6120 )
6121 }
6122 __tmp.put_u64_le(self.capabilities.bits());
6123 __tmp.put_u64_le(self.uid);
6124 __tmp.put_u32_le(self.flight_sw_version);
6125 __tmp.put_u32_le(self.middleware_sw_version);
6126 __tmp.put_u32_le(self.os_sw_version);
6127 __tmp.put_u32_le(self.board_version);
6128 __tmp.put_u16_le(self.vendor_id);
6129 __tmp.put_u16_le(self.product_id);
6130 for val in &self.flight_custom_version {
6131 __tmp.put_u8(*val);
6132 }
6133 for val in &self.middleware_custom_version {
6134 __tmp.put_u8(*val);
6135 }
6136 for val in &self.os_custom_version {
6137 __tmp.put_u8(*val);
6138 }
6139 for val in &self.uid2 {
6140 __tmp.put_u8(*val);
6141 }
6142 if matches!(version, MavlinkVersion::V2) {
6143 let len = __tmp.len();
6144 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6145 } else {
6146 __tmp.len()
6147 }
6148 }
6149}
6150#[doc = "id: 435"]
6151#[doc = "Information about a flight mode. The message can be enumerated to get information for all modes, or requested for a particular mode, using MAV_CMD_REQUEST_MESSAGE. Specify 0 in param2 to request that the message is emitted for all available modes or the specific index for just one mode. The modes must be available/settable for the current vehicle/frame type. Each mode should only be emitted once (even if it is both standard and custom). Note that the current mode should be emitted in CURRENT_MODE, and that if the mode list can change then AVAILABLE_MODES_MONITOR must be emitted on first change and subsequently streamed. See <https://mavlink.io/en/services/standard_modes.html>."]
6152#[derive(Debug, Clone, PartialEq)]
6153#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6154#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6155pub struct AVAILABLE_MODES_DATA {
6156 #[doc = "A bitfield for use for autopilot-specific flags"]
6157 pub custom_mode: u32,
6158 #[doc = "Mode properties."]
6159 pub properties: MavModeProperty,
6160 #[doc = "The total number of available modes for the current vehicle type."]
6161 pub number_modes: u8,
6162 #[doc = "The current mode index within number_modes, indexed from 1. The index is not guaranteed to be persistent, and may change between reboots or if the set of modes change."]
6163 pub mode_index: u8,
6164 #[doc = "Standard mode."]
6165 pub standard_mode: MavStandardMode,
6166 #[doc = "Name of custom mode, with null termination character. Should be omitted for standard modes."]
6167 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6168 pub mode_name: [u8; 35],
6169}
6170impl AVAILABLE_MODES_DATA {
6171 pub const ENCODED_LEN: usize = 46usize;
6172 pub const DEFAULT: Self = Self {
6173 custom_mode: 0_u32,
6174 properties: MavModeProperty::DEFAULT,
6175 number_modes: 0_u8,
6176 mode_index: 0_u8,
6177 standard_mode: MavStandardMode::DEFAULT,
6178 mode_name: [0_u8; 35usize],
6179 };
6180 #[cfg(feature = "arbitrary")]
6181 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6182 use arbitrary::{Arbitrary, Unstructured};
6183 let mut buf = [0u8; 1024];
6184 rng.fill_bytes(&mut buf);
6185 let mut unstructured = Unstructured::new(&buf);
6186 Self::arbitrary(&mut unstructured).unwrap_or_default()
6187 }
6188}
6189impl Default for AVAILABLE_MODES_DATA {
6190 fn default() -> Self {
6191 Self::DEFAULT.clone()
6192 }
6193}
6194impl MessageData for AVAILABLE_MODES_DATA {
6195 type Message = MavMessage;
6196 const ID: u32 = 435u32;
6197 const NAME: &'static str = "AVAILABLE_MODES";
6198 const EXTRA_CRC: u8 = 134u8;
6199 const ENCODED_LEN: usize = 46usize;
6200 fn deser(
6201 _version: MavlinkVersion,
6202 __input: &[u8],
6203 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6204 let avail_len = __input.len();
6205 let mut payload_buf = [0; Self::ENCODED_LEN];
6206 let mut buf = if avail_len < Self::ENCODED_LEN {
6207 payload_buf[0..avail_len].copy_from_slice(__input);
6208 Bytes::new(&payload_buf)
6209 } else {
6210 Bytes::new(__input)
6211 };
6212 let mut __struct = Self::default();
6213 __struct.custom_mode = buf.get_u32_le();
6214 let tmp = buf.get_u32_le();
6215 __struct.properties = MavModeProperty::from_bits(tmp & MavModeProperty::all().bits())
6216 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
6217 flag_type: "MavModeProperty",
6218 value: tmp as u32,
6219 })?;
6220 __struct.number_modes = buf.get_u8();
6221 __struct.mode_index = buf.get_u8();
6222 let tmp = buf.get_u8();
6223 __struct.standard_mode =
6224 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6225 enum_type: "MavStandardMode",
6226 value: tmp as u32,
6227 })?;
6228 for v in &mut __struct.mode_name {
6229 let val = buf.get_u8();
6230 *v = val;
6231 }
6232 Ok(__struct)
6233 }
6234 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6235 let mut __tmp = BytesMut::new(bytes);
6236 #[allow(clippy::absurd_extreme_comparisons)]
6237 #[allow(unused_comparisons)]
6238 if __tmp.remaining() < Self::ENCODED_LEN {
6239 panic!(
6240 "buffer is too small (need {} bytes, but got {})",
6241 Self::ENCODED_LEN,
6242 __tmp.remaining(),
6243 )
6244 }
6245 __tmp.put_u32_le(self.custom_mode);
6246 __tmp.put_u32_le(self.properties.bits());
6247 __tmp.put_u8(self.number_modes);
6248 __tmp.put_u8(self.mode_index);
6249 __tmp.put_u8(self.standard_mode as u8);
6250 for val in &self.mode_name {
6251 __tmp.put_u8(*val);
6252 }
6253 if matches!(version, MavlinkVersion::V2) {
6254 let len = __tmp.len();
6255 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6256 } else {
6257 __tmp.len()
6258 }
6259 }
6260}
6261#[doc = "id: 437"]
6262#[doc = "A change to the sequence number indicates that the set of AVAILABLE_MODES has changed. A receiver must re-request all available modes whenever the sequence number changes. This is only emitted after the first change and should then be broadcast at low rate (nominally 0.3 Hz) and on change. See <https://mavlink.io/en/services/standard_modes.html>."]
6263#[derive(Debug, Clone, PartialEq)]
6264#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6265#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6266pub struct AVAILABLE_MODES_MONITOR_DATA {
6267 #[doc = "Sequence number. The value iterates sequentially whenever AVAILABLE_MODES changes (e.g. support for a new mode is added/removed dynamically)."]
6268 pub seq: u8,
6269}
6270impl AVAILABLE_MODES_MONITOR_DATA {
6271 pub const ENCODED_LEN: usize = 1usize;
6272 pub const DEFAULT: Self = Self { seq: 0_u8 };
6273 #[cfg(feature = "arbitrary")]
6274 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6275 use arbitrary::{Arbitrary, Unstructured};
6276 let mut buf = [0u8; 1024];
6277 rng.fill_bytes(&mut buf);
6278 let mut unstructured = Unstructured::new(&buf);
6279 Self::arbitrary(&mut unstructured).unwrap_or_default()
6280 }
6281}
6282impl Default for AVAILABLE_MODES_MONITOR_DATA {
6283 fn default() -> Self {
6284 Self::DEFAULT.clone()
6285 }
6286}
6287impl MessageData for AVAILABLE_MODES_MONITOR_DATA {
6288 type Message = MavMessage;
6289 const ID: u32 = 437u32;
6290 const NAME: &'static str = "AVAILABLE_MODES_MONITOR";
6291 const EXTRA_CRC: u8 = 30u8;
6292 const ENCODED_LEN: usize = 1usize;
6293 fn deser(
6294 _version: MavlinkVersion,
6295 __input: &[u8],
6296 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6297 let avail_len = __input.len();
6298 let mut payload_buf = [0; Self::ENCODED_LEN];
6299 let mut buf = if avail_len < Self::ENCODED_LEN {
6300 payload_buf[0..avail_len].copy_from_slice(__input);
6301 Bytes::new(&payload_buf)
6302 } else {
6303 Bytes::new(__input)
6304 };
6305 let mut __struct = Self::default();
6306 __struct.seq = buf.get_u8();
6307 Ok(__struct)
6308 }
6309 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6310 let mut __tmp = BytesMut::new(bytes);
6311 #[allow(clippy::absurd_extreme_comparisons)]
6312 #[allow(unused_comparisons)]
6313 if __tmp.remaining() < Self::ENCODED_LEN {
6314 panic!(
6315 "buffer is too small (need {} bytes, but got {})",
6316 Self::ENCODED_LEN,
6317 __tmp.remaining(),
6318 )
6319 }
6320 __tmp.put_u8(self.seq);
6321 if matches!(version, MavlinkVersion::V2) {
6322 let len = __tmp.len();
6323 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6324 } else {
6325 __tmp.len()
6326 }
6327 }
6328}
6329#[doc = "id: 372"]
6330#[doc = "Battery information that is static, or requires infrequent update. This message should requested using MAV_CMD_REQUEST_MESSAGE and/or streamed at very low rate. BATTERY_STATUS_V2 is used for higher-rate battery status information."]
6331#[derive(Debug, Clone, PartialEq)]
6332#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6333#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6334pub struct BATTERY_INFO_DATA {
6335 #[doc = "Minimum per-cell voltage when discharging. 0: field not provided."]
6336 pub discharge_minimum_voltage: f32,
6337 #[doc = "Minimum per-cell voltage when charging. 0: field not provided."]
6338 pub charging_minimum_voltage: f32,
6339 #[doc = "Minimum per-cell voltage when resting. 0: field not provided."]
6340 pub resting_minimum_voltage: f32,
6341 #[doc = "Maximum per-cell voltage when charged. 0: field not provided."]
6342 pub charging_maximum_voltage: f32,
6343 #[doc = "Maximum pack continuous charge current. 0: field not provided."]
6344 pub charging_maximum_current: f32,
6345 #[doc = "Battery nominal voltage. Used for conversion between Wh and Ah. 0: field not provided."]
6346 pub nominal_voltage: f32,
6347 #[doc = "Maximum pack discharge current. 0: field not provided."]
6348 pub discharge_maximum_current: f32,
6349 #[doc = "Maximum pack discharge burst current. 0: field not provided."]
6350 pub discharge_maximum_burst_current: f32,
6351 #[doc = "Fully charged design capacity. 0: field not provided."]
6352 pub design_capacity: f32,
6353 #[doc = "Predicted battery capacity when fully charged (accounting for battery degradation). NAN: field not provided."]
6354 pub full_charge_capacity: f32,
6355 #[doc = "Lifetime count of the number of charge/discharge cycles (<https://en.wikipedia.org/wiki/Charge_cycle>). UINT16_MAX: field not provided."]
6356 pub cycle_count: u16,
6357 #[doc = "Battery weight. 0: field not provided."]
6358 pub weight: u16,
6359 #[doc = "Battery ID"]
6360 pub id: u8,
6361 #[doc = "Function of the battery."]
6362 pub battery_function: MavBatteryFunction,
6363 #[doc = "Type (chemistry) of the battery."]
6364 pub mavtype: MavBatteryType,
6365 #[doc = "State of Health (SOH) estimate. Typically 100% at the time of manufacture and will decrease over time and use. -1: field not provided."]
6366 pub state_of_health: u8,
6367 #[doc = "Number of battery cells in series. 0: field not provided."]
6368 pub cells_in_series: u8,
6369 #[doc = "Manufacture date (DDMMYYYY) in ASCII characters, 0 terminated. All 0: field not provided."]
6370 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6371 pub manufacture_date: [u8; 9],
6372 #[doc = "Serial number in ASCII characters, 0 terminated. All 0: field not provided."]
6373 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6374 pub serial_number: [u8; 32],
6375 #[doc = "Battery device name. Formatted as manufacturer name then product name, separated with an underscore (in ASCII characters), 0 terminated. All 0: field not provided."]
6376 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6377 pub name: [u8; 50],
6378}
6379impl BATTERY_INFO_DATA {
6380 pub const ENCODED_LEN: usize = 140usize;
6381 pub const DEFAULT: Self = Self {
6382 discharge_minimum_voltage: 0.0_f32,
6383 charging_minimum_voltage: 0.0_f32,
6384 resting_minimum_voltage: 0.0_f32,
6385 charging_maximum_voltage: 0.0_f32,
6386 charging_maximum_current: 0.0_f32,
6387 nominal_voltage: 0.0_f32,
6388 discharge_maximum_current: 0.0_f32,
6389 discharge_maximum_burst_current: 0.0_f32,
6390 design_capacity: 0.0_f32,
6391 full_charge_capacity: 0.0_f32,
6392 cycle_count: 0_u16,
6393 weight: 0_u16,
6394 id: 0_u8,
6395 battery_function: MavBatteryFunction::DEFAULT,
6396 mavtype: MavBatteryType::DEFAULT,
6397 state_of_health: 0_u8,
6398 cells_in_series: 0_u8,
6399 manufacture_date: [0_u8; 9usize],
6400 serial_number: [0_u8; 32usize],
6401 name: [0_u8; 50usize],
6402 };
6403 #[cfg(feature = "arbitrary")]
6404 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6405 use arbitrary::{Arbitrary, Unstructured};
6406 let mut buf = [0u8; 1024];
6407 rng.fill_bytes(&mut buf);
6408 let mut unstructured = Unstructured::new(&buf);
6409 Self::arbitrary(&mut unstructured).unwrap_or_default()
6410 }
6411}
6412impl Default for BATTERY_INFO_DATA {
6413 fn default() -> Self {
6414 Self::DEFAULT.clone()
6415 }
6416}
6417impl MessageData for BATTERY_INFO_DATA {
6418 type Message = MavMessage;
6419 const ID: u32 = 372u32;
6420 const NAME: &'static str = "BATTERY_INFO";
6421 const EXTRA_CRC: u8 = 26u8;
6422 const ENCODED_LEN: usize = 140usize;
6423 fn deser(
6424 _version: MavlinkVersion,
6425 __input: &[u8],
6426 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6427 let avail_len = __input.len();
6428 let mut payload_buf = [0; Self::ENCODED_LEN];
6429 let mut buf = if avail_len < Self::ENCODED_LEN {
6430 payload_buf[0..avail_len].copy_from_slice(__input);
6431 Bytes::new(&payload_buf)
6432 } else {
6433 Bytes::new(__input)
6434 };
6435 let mut __struct = Self::default();
6436 __struct.discharge_minimum_voltage = buf.get_f32_le();
6437 __struct.charging_minimum_voltage = buf.get_f32_le();
6438 __struct.resting_minimum_voltage = buf.get_f32_le();
6439 __struct.charging_maximum_voltage = buf.get_f32_le();
6440 __struct.charging_maximum_current = buf.get_f32_le();
6441 __struct.nominal_voltage = buf.get_f32_le();
6442 __struct.discharge_maximum_current = buf.get_f32_le();
6443 __struct.discharge_maximum_burst_current = buf.get_f32_le();
6444 __struct.design_capacity = buf.get_f32_le();
6445 __struct.full_charge_capacity = buf.get_f32_le();
6446 __struct.cycle_count = buf.get_u16_le();
6447 __struct.weight = buf.get_u16_le();
6448 __struct.id = buf.get_u8();
6449 let tmp = buf.get_u8();
6450 __struct.battery_function =
6451 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6452 enum_type: "MavBatteryFunction",
6453 value: tmp as u32,
6454 })?;
6455 let tmp = buf.get_u8();
6456 __struct.mavtype =
6457 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6458 enum_type: "MavBatteryType",
6459 value: tmp as u32,
6460 })?;
6461 __struct.state_of_health = buf.get_u8();
6462 __struct.cells_in_series = buf.get_u8();
6463 for v in &mut __struct.manufacture_date {
6464 let val = buf.get_u8();
6465 *v = val;
6466 }
6467 for v in &mut __struct.serial_number {
6468 let val = buf.get_u8();
6469 *v = val;
6470 }
6471 for v in &mut __struct.name {
6472 let val = buf.get_u8();
6473 *v = val;
6474 }
6475 Ok(__struct)
6476 }
6477 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6478 let mut __tmp = BytesMut::new(bytes);
6479 #[allow(clippy::absurd_extreme_comparisons)]
6480 #[allow(unused_comparisons)]
6481 if __tmp.remaining() < Self::ENCODED_LEN {
6482 panic!(
6483 "buffer is too small (need {} bytes, but got {})",
6484 Self::ENCODED_LEN,
6485 __tmp.remaining(),
6486 )
6487 }
6488 __tmp.put_f32_le(self.discharge_minimum_voltage);
6489 __tmp.put_f32_le(self.charging_minimum_voltage);
6490 __tmp.put_f32_le(self.resting_minimum_voltage);
6491 __tmp.put_f32_le(self.charging_maximum_voltage);
6492 __tmp.put_f32_le(self.charging_maximum_current);
6493 __tmp.put_f32_le(self.nominal_voltage);
6494 __tmp.put_f32_le(self.discharge_maximum_current);
6495 __tmp.put_f32_le(self.discharge_maximum_burst_current);
6496 __tmp.put_f32_le(self.design_capacity);
6497 __tmp.put_f32_le(self.full_charge_capacity);
6498 __tmp.put_u16_le(self.cycle_count);
6499 __tmp.put_u16_le(self.weight);
6500 __tmp.put_u8(self.id);
6501 __tmp.put_u8(self.battery_function as u8);
6502 __tmp.put_u8(self.mavtype as u8);
6503 __tmp.put_u8(self.state_of_health);
6504 __tmp.put_u8(self.cells_in_series);
6505 for val in &self.manufacture_date {
6506 __tmp.put_u8(*val);
6507 }
6508 for val in &self.serial_number {
6509 __tmp.put_u8(*val);
6510 }
6511 for val in &self.name {
6512 __tmp.put_u8(*val);
6513 }
6514 if matches!(version, MavlinkVersion::V2) {
6515 let len = __tmp.len();
6516 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6517 } else {
6518 __tmp.len()
6519 }
6520 }
6521}
6522#[doc = "id: 147"]
6523#[doc = "Battery information. Updates GCS with flight controller battery status. Smart batteries also use this message, but may additionally send BATTERY_INFO."]
6524#[derive(Debug, Clone, PartialEq)]
6525#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6526#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6527pub struct BATTERY_STATUS_DATA {
6528 #[doc = "Consumed charge, -1: autopilot does not provide consumption estimate"]
6529 pub current_consumed: i32,
6530 #[doc = "Consumed energy, -1: autopilot does not provide energy consumption estimate"]
6531 pub energy_consumed: i32,
6532 #[doc = "Temperature of the battery. INT16_MAX for unknown temperature."]
6533 pub temperature: i16,
6534 #[doc = "Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1)."]
6535 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6536 pub voltages: [u16; 10],
6537 #[doc = "Battery current, -1: autopilot does not measure the current"]
6538 pub current_battery: i16,
6539 #[doc = "Battery ID"]
6540 pub id: u8,
6541 #[doc = "Function of the battery"]
6542 pub battery_function: MavBatteryFunction,
6543 #[doc = "Type (chemistry) of the battery"]
6544 pub mavtype: MavBatteryType,
6545 #[doc = "Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery."]
6546 pub battery_remaining: i8,
6547 #[doc = "Remaining battery time, 0: autopilot does not provide remaining battery time estimate"]
6548 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6549 pub time_remaining: i32,
6550 #[doc = "State for extent of discharge, provided by autopilot for warning or external reactions"]
6551 #[cfg_attr(feature = "serde", serde(default))]
6552 pub charge_state: MavBatteryChargeState,
6553 #[doc = "Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead."]
6554 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6555 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6556 pub voltages_ext: [u16; 4],
6557 #[doc = "Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode."]
6558 #[cfg_attr(feature = "serde", serde(default))]
6559 pub mode: MavBatteryMode,
6560 #[doc = "Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported)."]
6561 #[cfg_attr(feature = "serde", serde(default))]
6562 pub fault_bitmask: MavBatteryFault,
6563}
6564impl BATTERY_STATUS_DATA {
6565 pub const ENCODED_LEN: usize = 54usize;
6566 pub const DEFAULT: Self = Self {
6567 current_consumed: 0_i32,
6568 energy_consumed: 0_i32,
6569 temperature: 0_i16,
6570 voltages: [0_u16; 10usize],
6571 current_battery: 0_i16,
6572 id: 0_u8,
6573 battery_function: MavBatteryFunction::DEFAULT,
6574 mavtype: MavBatteryType::DEFAULT,
6575 battery_remaining: 0_i8,
6576 time_remaining: 0_i32,
6577 charge_state: MavBatteryChargeState::DEFAULT,
6578 voltages_ext: [0_u16; 4usize],
6579 mode: MavBatteryMode::DEFAULT,
6580 fault_bitmask: MavBatteryFault::DEFAULT,
6581 };
6582 #[cfg(feature = "arbitrary")]
6583 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6584 use arbitrary::{Arbitrary, Unstructured};
6585 let mut buf = [0u8; 1024];
6586 rng.fill_bytes(&mut buf);
6587 let mut unstructured = Unstructured::new(&buf);
6588 Self::arbitrary(&mut unstructured).unwrap_or_default()
6589 }
6590}
6591impl Default for BATTERY_STATUS_DATA {
6592 fn default() -> Self {
6593 Self::DEFAULT.clone()
6594 }
6595}
6596impl MessageData for BATTERY_STATUS_DATA {
6597 type Message = MavMessage;
6598 const ID: u32 = 147u32;
6599 const NAME: &'static str = "BATTERY_STATUS";
6600 const EXTRA_CRC: u8 = 154u8;
6601 const ENCODED_LEN: usize = 54usize;
6602 fn deser(
6603 _version: MavlinkVersion,
6604 __input: &[u8],
6605 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6606 let avail_len = __input.len();
6607 let mut payload_buf = [0; Self::ENCODED_LEN];
6608 let mut buf = if avail_len < Self::ENCODED_LEN {
6609 payload_buf[0..avail_len].copy_from_slice(__input);
6610 Bytes::new(&payload_buf)
6611 } else {
6612 Bytes::new(__input)
6613 };
6614 let mut __struct = Self::default();
6615 __struct.current_consumed = buf.get_i32_le();
6616 __struct.energy_consumed = buf.get_i32_le();
6617 __struct.temperature = buf.get_i16_le();
6618 for v in &mut __struct.voltages {
6619 let val = buf.get_u16_le();
6620 *v = val;
6621 }
6622 __struct.current_battery = buf.get_i16_le();
6623 __struct.id = buf.get_u8();
6624 let tmp = buf.get_u8();
6625 __struct.battery_function =
6626 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6627 enum_type: "MavBatteryFunction",
6628 value: tmp as u32,
6629 })?;
6630 let tmp = buf.get_u8();
6631 __struct.mavtype =
6632 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6633 enum_type: "MavBatteryType",
6634 value: tmp as u32,
6635 })?;
6636 __struct.battery_remaining = buf.get_i8();
6637 __struct.time_remaining = buf.get_i32_le();
6638 let tmp = buf.get_u8();
6639 __struct.charge_state =
6640 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6641 enum_type: "MavBatteryChargeState",
6642 value: tmp as u32,
6643 })?;
6644 for v in &mut __struct.voltages_ext {
6645 let val = buf.get_u16_le();
6646 *v = val;
6647 }
6648 let tmp = buf.get_u8();
6649 __struct.mode =
6650 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6651 enum_type: "MavBatteryMode",
6652 value: tmp as u32,
6653 })?;
6654 let tmp = buf.get_u32_le();
6655 __struct.fault_bitmask = MavBatteryFault::from_bits(tmp & MavBatteryFault::all().bits())
6656 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
6657 flag_type: "MavBatteryFault",
6658 value: tmp as u32,
6659 })?;
6660 Ok(__struct)
6661 }
6662 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6663 let mut __tmp = BytesMut::new(bytes);
6664 #[allow(clippy::absurd_extreme_comparisons)]
6665 #[allow(unused_comparisons)]
6666 if __tmp.remaining() < Self::ENCODED_LEN {
6667 panic!(
6668 "buffer is too small (need {} bytes, but got {})",
6669 Self::ENCODED_LEN,
6670 __tmp.remaining(),
6671 )
6672 }
6673 __tmp.put_i32_le(self.current_consumed);
6674 __tmp.put_i32_le(self.energy_consumed);
6675 __tmp.put_i16_le(self.temperature);
6676 for val in &self.voltages {
6677 __tmp.put_u16_le(*val);
6678 }
6679 __tmp.put_i16_le(self.current_battery);
6680 __tmp.put_u8(self.id);
6681 __tmp.put_u8(self.battery_function as u8);
6682 __tmp.put_u8(self.mavtype as u8);
6683 __tmp.put_i8(self.battery_remaining);
6684 __tmp.put_i32_le(self.time_remaining);
6685 __tmp.put_u8(self.charge_state as u8);
6686 for val in &self.voltages_ext {
6687 __tmp.put_u16_le(*val);
6688 }
6689 __tmp.put_u8(self.mode as u8);
6690 __tmp.put_u32_le(self.fault_bitmask.bits());
6691 if matches!(version, MavlinkVersion::V2) {
6692 let len = __tmp.len();
6693 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6694 } else {
6695 __tmp.len()
6696 }
6697 }
6698}
6699#[doc = "id: 257"]
6700#[doc = "Report button state change."]
6701#[derive(Debug, Clone, PartialEq)]
6702#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6703#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6704pub struct BUTTON_CHANGE_DATA {
6705 #[doc = "Timestamp (time since system boot)."]
6706 pub time_boot_ms: u32,
6707 #[doc = "Time of last change of button state."]
6708 pub last_change_ms: u32,
6709 #[doc = "Bitmap for state of buttons."]
6710 pub state: u8,
6711}
6712impl BUTTON_CHANGE_DATA {
6713 pub const ENCODED_LEN: usize = 9usize;
6714 pub const DEFAULT: Self = Self {
6715 time_boot_ms: 0_u32,
6716 last_change_ms: 0_u32,
6717 state: 0_u8,
6718 };
6719 #[cfg(feature = "arbitrary")]
6720 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6721 use arbitrary::{Arbitrary, Unstructured};
6722 let mut buf = [0u8; 1024];
6723 rng.fill_bytes(&mut buf);
6724 let mut unstructured = Unstructured::new(&buf);
6725 Self::arbitrary(&mut unstructured).unwrap_or_default()
6726 }
6727}
6728impl Default for BUTTON_CHANGE_DATA {
6729 fn default() -> Self {
6730 Self::DEFAULT.clone()
6731 }
6732}
6733impl MessageData for BUTTON_CHANGE_DATA {
6734 type Message = MavMessage;
6735 const ID: u32 = 257u32;
6736 const NAME: &'static str = "BUTTON_CHANGE";
6737 const EXTRA_CRC: u8 = 131u8;
6738 const ENCODED_LEN: usize = 9usize;
6739 fn deser(
6740 _version: MavlinkVersion,
6741 __input: &[u8],
6742 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6743 let avail_len = __input.len();
6744 let mut payload_buf = [0; Self::ENCODED_LEN];
6745 let mut buf = if avail_len < Self::ENCODED_LEN {
6746 payload_buf[0..avail_len].copy_from_slice(__input);
6747 Bytes::new(&payload_buf)
6748 } else {
6749 Bytes::new(__input)
6750 };
6751 let mut __struct = Self::default();
6752 __struct.time_boot_ms = buf.get_u32_le();
6753 __struct.last_change_ms = buf.get_u32_le();
6754 __struct.state = buf.get_u8();
6755 Ok(__struct)
6756 }
6757 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6758 let mut __tmp = BytesMut::new(bytes);
6759 #[allow(clippy::absurd_extreme_comparisons)]
6760 #[allow(unused_comparisons)]
6761 if __tmp.remaining() < Self::ENCODED_LEN {
6762 panic!(
6763 "buffer is too small (need {} bytes, but got {})",
6764 Self::ENCODED_LEN,
6765 __tmp.remaining(),
6766 )
6767 }
6768 __tmp.put_u32_le(self.time_boot_ms);
6769 __tmp.put_u32_le(self.last_change_ms);
6770 __tmp.put_u8(self.state);
6771 if matches!(version, MavlinkVersion::V2) {
6772 let len = __tmp.len();
6773 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6774 } else {
6775 __tmp.len()
6776 }
6777 }
6778}
6779#[doc = "id: 262"]
6780#[doc = "Information about the status of a capture. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
6781#[derive(Debug, Clone, PartialEq)]
6782#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6783#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6784pub struct CAMERA_CAPTURE_STATUS_DATA {
6785 #[doc = "Timestamp (time since system boot)."]
6786 pub time_boot_ms: u32,
6787 #[doc = "Image capture interval"]
6788 pub image_interval: f32,
6789 #[doc = "Elapsed time since recording started (0: Not supported/available). A GCS should compute recording time and use non-zero values of this field to correct any discrepancy."]
6790 pub recording_time_ms: u32,
6791 #[doc = "Available storage capacity."]
6792 pub available_capacity: f32,
6793 #[doc = "Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress)"]
6794 pub image_status: u8,
6795 #[doc = "Current status of video capturing (0: idle, 1: capture in progress)"]
6796 pub video_status: u8,
6797 #[doc = "Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT)."]
6798 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6799 pub image_count: i32,
6800 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
6801 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6802 pub camera_device_id: u8,
6803}
6804impl CAMERA_CAPTURE_STATUS_DATA {
6805 pub const ENCODED_LEN: usize = 23usize;
6806 pub const DEFAULT: Self = Self {
6807 time_boot_ms: 0_u32,
6808 image_interval: 0.0_f32,
6809 recording_time_ms: 0_u32,
6810 available_capacity: 0.0_f32,
6811 image_status: 0_u8,
6812 video_status: 0_u8,
6813 image_count: 0_i32,
6814 camera_device_id: 0_u8,
6815 };
6816 #[cfg(feature = "arbitrary")]
6817 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6818 use arbitrary::{Arbitrary, Unstructured};
6819 let mut buf = [0u8; 1024];
6820 rng.fill_bytes(&mut buf);
6821 let mut unstructured = Unstructured::new(&buf);
6822 Self::arbitrary(&mut unstructured).unwrap_or_default()
6823 }
6824}
6825impl Default for CAMERA_CAPTURE_STATUS_DATA {
6826 fn default() -> Self {
6827 Self::DEFAULT.clone()
6828 }
6829}
6830impl MessageData for CAMERA_CAPTURE_STATUS_DATA {
6831 type Message = MavMessage;
6832 const ID: u32 = 262u32;
6833 const NAME: &'static str = "CAMERA_CAPTURE_STATUS";
6834 const EXTRA_CRC: u8 = 12u8;
6835 const ENCODED_LEN: usize = 23usize;
6836 fn deser(
6837 _version: MavlinkVersion,
6838 __input: &[u8],
6839 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6840 let avail_len = __input.len();
6841 let mut payload_buf = [0; Self::ENCODED_LEN];
6842 let mut buf = if avail_len < Self::ENCODED_LEN {
6843 payload_buf[0..avail_len].copy_from_slice(__input);
6844 Bytes::new(&payload_buf)
6845 } else {
6846 Bytes::new(__input)
6847 };
6848 let mut __struct = Self::default();
6849 __struct.time_boot_ms = buf.get_u32_le();
6850 __struct.image_interval = buf.get_f32_le();
6851 __struct.recording_time_ms = buf.get_u32_le();
6852 __struct.available_capacity = buf.get_f32_le();
6853 __struct.image_status = buf.get_u8();
6854 __struct.video_status = buf.get_u8();
6855 __struct.image_count = buf.get_i32_le();
6856 __struct.camera_device_id = buf.get_u8();
6857 Ok(__struct)
6858 }
6859 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6860 let mut __tmp = BytesMut::new(bytes);
6861 #[allow(clippy::absurd_extreme_comparisons)]
6862 #[allow(unused_comparisons)]
6863 if __tmp.remaining() < Self::ENCODED_LEN {
6864 panic!(
6865 "buffer is too small (need {} bytes, but got {})",
6866 Self::ENCODED_LEN,
6867 __tmp.remaining(),
6868 )
6869 }
6870 __tmp.put_u32_le(self.time_boot_ms);
6871 __tmp.put_f32_le(self.image_interval);
6872 __tmp.put_u32_le(self.recording_time_ms);
6873 __tmp.put_f32_le(self.available_capacity);
6874 __tmp.put_u8(self.image_status);
6875 __tmp.put_u8(self.video_status);
6876 __tmp.put_i32_le(self.image_count);
6877 __tmp.put_u8(self.camera_device_id);
6878 if matches!(version, MavlinkVersion::V2) {
6879 let len = __tmp.len();
6880 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6881 } else {
6882 __tmp.len()
6883 }
6884 }
6885}
6886#[doc = "id: 271"]
6887#[doc = "Information about the field of view of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
6888#[derive(Debug, Clone, PartialEq)]
6889#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6890#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6891pub struct CAMERA_FOV_STATUS_DATA {
6892 #[doc = "Timestamp (time since system boot)."]
6893 pub time_boot_ms: u32,
6894 #[doc = "Latitude of camera (INT32_MAX if unknown)."]
6895 pub lat_camera: i32,
6896 #[doc = "Longitude of camera (INT32_MAX if unknown)."]
6897 pub lon_camera: i32,
6898 #[doc = "Altitude (MSL) of camera (INT32_MAX if unknown)."]
6899 pub alt_camera: i32,
6900 #[doc = "Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon)."]
6901 pub lat_image: i32,
6902 #[doc = "Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon)."]
6903 pub lon_image: i32,
6904 #[doc = "Altitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon)."]
6905 pub alt_image: i32,
6906 #[doc = "Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
6907 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6908 pub q: [f32; 4],
6909 #[doc = "Horizontal field of view (NaN if unknown)."]
6910 pub hfov: f32,
6911 #[doc = "Vertical field of view (NaN if unknown)."]
6912 pub vfov: f32,
6913 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
6914 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6915 pub camera_device_id: u8,
6916}
6917impl CAMERA_FOV_STATUS_DATA {
6918 pub const ENCODED_LEN: usize = 53usize;
6919 pub const DEFAULT: Self = Self {
6920 time_boot_ms: 0_u32,
6921 lat_camera: 0_i32,
6922 lon_camera: 0_i32,
6923 alt_camera: 0_i32,
6924 lat_image: 0_i32,
6925 lon_image: 0_i32,
6926 alt_image: 0_i32,
6927 q: [0.0_f32; 4usize],
6928 hfov: 0.0_f32,
6929 vfov: 0.0_f32,
6930 camera_device_id: 0_u8,
6931 };
6932 #[cfg(feature = "arbitrary")]
6933 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6934 use arbitrary::{Arbitrary, Unstructured};
6935 let mut buf = [0u8; 1024];
6936 rng.fill_bytes(&mut buf);
6937 let mut unstructured = Unstructured::new(&buf);
6938 Self::arbitrary(&mut unstructured).unwrap_or_default()
6939 }
6940}
6941impl Default for CAMERA_FOV_STATUS_DATA {
6942 fn default() -> Self {
6943 Self::DEFAULT.clone()
6944 }
6945}
6946impl MessageData for CAMERA_FOV_STATUS_DATA {
6947 type Message = MavMessage;
6948 const ID: u32 = 271u32;
6949 const NAME: &'static str = "CAMERA_FOV_STATUS";
6950 const EXTRA_CRC: u8 = 22u8;
6951 const ENCODED_LEN: usize = 53usize;
6952 fn deser(
6953 _version: MavlinkVersion,
6954 __input: &[u8],
6955 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6956 let avail_len = __input.len();
6957 let mut payload_buf = [0; Self::ENCODED_LEN];
6958 let mut buf = if avail_len < Self::ENCODED_LEN {
6959 payload_buf[0..avail_len].copy_from_slice(__input);
6960 Bytes::new(&payload_buf)
6961 } else {
6962 Bytes::new(__input)
6963 };
6964 let mut __struct = Self::default();
6965 __struct.time_boot_ms = buf.get_u32_le();
6966 __struct.lat_camera = buf.get_i32_le();
6967 __struct.lon_camera = buf.get_i32_le();
6968 __struct.alt_camera = buf.get_i32_le();
6969 __struct.lat_image = buf.get_i32_le();
6970 __struct.lon_image = buf.get_i32_le();
6971 __struct.alt_image = buf.get_i32_le();
6972 for v in &mut __struct.q {
6973 let val = buf.get_f32_le();
6974 *v = val;
6975 }
6976 __struct.hfov = buf.get_f32_le();
6977 __struct.vfov = buf.get_f32_le();
6978 __struct.camera_device_id = buf.get_u8();
6979 Ok(__struct)
6980 }
6981 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6982 let mut __tmp = BytesMut::new(bytes);
6983 #[allow(clippy::absurd_extreme_comparisons)]
6984 #[allow(unused_comparisons)]
6985 if __tmp.remaining() < Self::ENCODED_LEN {
6986 panic!(
6987 "buffer is too small (need {} bytes, but got {})",
6988 Self::ENCODED_LEN,
6989 __tmp.remaining(),
6990 )
6991 }
6992 __tmp.put_u32_le(self.time_boot_ms);
6993 __tmp.put_i32_le(self.lat_camera);
6994 __tmp.put_i32_le(self.lon_camera);
6995 __tmp.put_i32_le(self.alt_camera);
6996 __tmp.put_i32_le(self.lat_image);
6997 __tmp.put_i32_le(self.lon_image);
6998 __tmp.put_i32_le(self.alt_image);
6999 for val in &self.q {
7000 __tmp.put_f32_le(*val);
7001 }
7002 __tmp.put_f32_le(self.hfov);
7003 __tmp.put_f32_le(self.vfov);
7004 __tmp.put_u8(self.camera_device_id);
7005 if matches!(version, MavlinkVersion::V2) {
7006 let len = __tmp.len();
7007 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7008 } else {
7009 __tmp.len()
7010 }
7011 }
7012}
7013#[doc = "id: 263"]
7014#[doc = "Information about a captured image. This is emitted every time a message is captured. MAV_CMD_REQUEST_MESSAGE can be used to (re)request this message for a specific sequence number or range of sequence numbers: MAV_CMD_REQUEST_MESSAGE.param2 indicates the sequence number the first image to send, or set to -1 to send the message for all sequence numbers. MAV_CMD_REQUEST_MESSAGE.param3 is used to specify a range of messages to send: set to 0 (default) to send just the the message for the sequence number in param 2, set to -1 to send the message for the sequence number in param 2 and all the following sequence numbers, set to the sequence number of the final message in the range."]
7015#[derive(Debug, Clone, PartialEq)]
7016#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7017#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7018pub struct CAMERA_IMAGE_CAPTURED_DATA {
7019 #[doc = "Timestamp (time since UNIX epoch) in UTC. 0 for unknown."]
7020 pub time_utc: u64,
7021 #[doc = "Timestamp (time since system boot)."]
7022 pub time_boot_ms: u32,
7023 #[doc = "Latitude where image was taken"]
7024 pub lat: i32,
7025 #[doc = "Longitude where capture was taken"]
7026 pub lon: i32,
7027 #[doc = "Altitude (MSL) where image was taken"]
7028 pub alt: i32,
7029 #[doc = "Altitude above ground"]
7030 pub relative_alt: i32,
7031 #[doc = "Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
7032 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7033 pub q: [f32; 4],
7034 #[doc = "Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)"]
7035 pub image_index: i32,
7036 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id). Field name is usually camera_device_id."]
7037 pub camera_id: u8,
7038 #[doc = "Boolean indicating success (1) or failure (0) while capturing this image."]
7039 pub capture_result: i8,
7040 #[doc = "URL of image taken. Either local storage or <http://foo.jpg> if camera provides an HTTP interface."]
7041 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7042 pub file_url: [u8; 205],
7043}
7044impl CAMERA_IMAGE_CAPTURED_DATA {
7045 pub const ENCODED_LEN: usize = 255usize;
7046 pub const DEFAULT: Self = Self {
7047 time_utc: 0_u64,
7048 time_boot_ms: 0_u32,
7049 lat: 0_i32,
7050 lon: 0_i32,
7051 alt: 0_i32,
7052 relative_alt: 0_i32,
7053 q: [0.0_f32; 4usize],
7054 image_index: 0_i32,
7055 camera_id: 0_u8,
7056 capture_result: 0_i8,
7057 file_url: [0_u8; 205usize],
7058 };
7059 #[cfg(feature = "arbitrary")]
7060 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7061 use arbitrary::{Arbitrary, Unstructured};
7062 let mut buf = [0u8; 1024];
7063 rng.fill_bytes(&mut buf);
7064 let mut unstructured = Unstructured::new(&buf);
7065 Self::arbitrary(&mut unstructured).unwrap_or_default()
7066 }
7067}
7068impl Default for CAMERA_IMAGE_CAPTURED_DATA {
7069 fn default() -> Self {
7070 Self::DEFAULT.clone()
7071 }
7072}
7073impl MessageData for CAMERA_IMAGE_CAPTURED_DATA {
7074 type Message = MavMessage;
7075 const ID: u32 = 263u32;
7076 const NAME: &'static str = "CAMERA_IMAGE_CAPTURED";
7077 const EXTRA_CRC: u8 = 133u8;
7078 const ENCODED_LEN: usize = 255usize;
7079 fn deser(
7080 _version: MavlinkVersion,
7081 __input: &[u8],
7082 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7083 let avail_len = __input.len();
7084 let mut payload_buf = [0; Self::ENCODED_LEN];
7085 let mut buf = if avail_len < Self::ENCODED_LEN {
7086 payload_buf[0..avail_len].copy_from_slice(__input);
7087 Bytes::new(&payload_buf)
7088 } else {
7089 Bytes::new(__input)
7090 };
7091 let mut __struct = Self::default();
7092 __struct.time_utc = buf.get_u64_le();
7093 __struct.time_boot_ms = buf.get_u32_le();
7094 __struct.lat = buf.get_i32_le();
7095 __struct.lon = buf.get_i32_le();
7096 __struct.alt = buf.get_i32_le();
7097 __struct.relative_alt = buf.get_i32_le();
7098 for v in &mut __struct.q {
7099 let val = buf.get_f32_le();
7100 *v = val;
7101 }
7102 __struct.image_index = buf.get_i32_le();
7103 __struct.camera_id = buf.get_u8();
7104 __struct.capture_result = buf.get_i8();
7105 for v in &mut __struct.file_url {
7106 let val = buf.get_u8();
7107 *v = val;
7108 }
7109 Ok(__struct)
7110 }
7111 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7112 let mut __tmp = BytesMut::new(bytes);
7113 #[allow(clippy::absurd_extreme_comparisons)]
7114 #[allow(unused_comparisons)]
7115 if __tmp.remaining() < Self::ENCODED_LEN {
7116 panic!(
7117 "buffer is too small (need {} bytes, but got {})",
7118 Self::ENCODED_LEN,
7119 __tmp.remaining(),
7120 )
7121 }
7122 __tmp.put_u64_le(self.time_utc);
7123 __tmp.put_u32_le(self.time_boot_ms);
7124 __tmp.put_i32_le(self.lat);
7125 __tmp.put_i32_le(self.lon);
7126 __tmp.put_i32_le(self.alt);
7127 __tmp.put_i32_le(self.relative_alt);
7128 for val in &self.q {
7129 __tmp.put_f32_le(*val);
7130 }
7131 __tmp.put_i32_le(self.image_index);
7132 __tmp.put_u8(self.camera_id);
7133 __tmp.put_i8(self.capture_result);
7134 for val in &self.file_url {
7135 __tmp.put_u8(*val);
7136 }
7137 if matches!(version, MavlinkVersion::V2) {
7138 let len = __tmp.len();
7139 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7140 } else {
7141 __tmp.len()
7142 }
7143 }
7144}
7145#[doc = "id: 259"]
7146#[doc = "Information about a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
7147#[derive(Debug, Clone, PartialEq)]
7148#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7149#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7150pub struct CAMERA_INFORMATION_DATA {
7151 #[doc = "Timestamp (time since system boot)."]
7152 pub time_boot_ms: u32,
7153 #[doc = "0xff). Use 0 if not known."]
7154 pub firmware_version: u32,
7155 #[doc = "Focal length. Use NaN if not known."]
7156 pub focal_length: f32,
7157 #[doc = "Image sensor size horizontal. Use NaN if not known."]
7158 pub sensor_size_h: f32,
7159 #[doc = "Image sensor size vertical. Use NaN if not known."]
7160 pub sensor_size_v: f32,
7161 #[doc = "Bitmap of camera capability flags."]
7162 pub flags: CameraCapFlags,
7163 #[doc = "Horizontal image resolution. Use 0 if not known."]
7164 pub resolution_h: u16,
7165 #[doc = "Vertical image resolution. Use 0 if not known."]
7166 pub resolution_v: u16,
7167 #[doc = "Camera definition version (iteration). Use 0 if not known."]
7168 pub cam_definition_version: u16,
7169 #[doc = "Name of the camera vendor"]
7170 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7171 pub vendor_name: [u8; 32],
7172 #[doc = "Name of the camera model"]
7173 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7174 pub model_name: [u8; 32],
7175 #[doc = "Reserved for a lens ID. Use 0 if not known."]
7176 pub lens_id: u8,
7177 #[doc = "Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known."]
7178 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7179 pub cam_definition_uri: [u8; 140],
7180 #[doc = "Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera."]
7181 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7182 pub gimbal_device_id: u8,
7183 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
7184 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7185 pub camera_device_id: u8,
7186}
7187impl CAMERA_INFORMATION_DATA {
7188 pub const ENCODED_LEN: usize = 237usize;
7189 pub const DEFAULT: Self = Self {
7190 time_boot_ms: 0_u32,
7191 firmware_version: 0_u32,
7192 focal_length: 0.0_f32,
7193 sensor_size_h: 0.0_f32,
7194 sensor_size_v: 0.0_f32,
7195 flags: CameraCapFlags::DEFAULT,
7196 resolution_h: 0_u16,
7197 resolution_v: 0_u16,
7198 cam_definition_version: 0_u16,
7199 vendor_name: [0_u8; 32usize],
7200 model_name: [0_u8; 32usize],
7201 lens_id: 0_u8,
7202 cam_definition_uri: [0_u8; 140usize],
7203 gimbal_device_id: 0_u8,
7204 camera_device_id: 0_u8,
7205 };
7206 #[cfg(feature = "arbitrary")]
7207 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7208 use arbitrary::{Arbitrary, Unstructured};
7209 let mut buf = [0u8; 1024];
7210 rng.fill_bytes(&mut buf);
7211 let mut unstructured = Unstructured::new(&buf);
7212 Self::arbitrary(&mut unstructured).unwrap_or_default()
7213 }
7214}
7215impl Default for CAMERA_INFORMATION_DATA {
7216 fn default() -> Self {
7217 Self::DEFAULT.clone()
7218 }
7219}
7220impl MessageData for CAMERA_INFORMATION_DATA {
7221 type Message = MavMessage;
7222 const ID: u32 = 259u32;
7223 const NAME: &'static str = "CAMERA_INFORMATION";
7224 const EXTRA_CRC: u8 = 92u8;
7225 const ENCODED_LEN: usize = 237usize;
7226 fn deser(
7227 _version: MavlinkVersion,
7228 __input: &[u8],
7229 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7230 let avail_len = __input.len();
7231 let mut payload_buf = [0; Self::ENCODED_LEN];
7232 let mut buf = if avail_len < Self::ENCODED_LEN {
7233 payload_buf[0..avail_len].copy_from_slice(__input);
7234 Bytes::new(&payload_buf)
7235 } else {
7236 Bytes::new(__input)
7237 };
7238 let mut __struct = Self::default();
7239 __struct.time_boot_ms = buf.get_u32_le();
7240 __struct.firmware_version = buf.get_u32_le();
7241 __struct.focal_length = buf.get_f32_le();
7242 __struct.sensor_size_h = buf.get_f32_le();
7243 __struct.sensor_size_v = buf.get_f32_le();
7244 let tmp = buf.get_u32_le();
7245 __struct.flags = CameraCapFlags::from_bits(tmp & CameraCapFlags::all().bits()).ok_or(
7246 ::mavlink_core::error::ParserError::InvalidFlag {
7247 flag_type: "CameraCapFlags",
7248 value: tmp as u32,
7249 },
7250 )?;
7251 __struct.resolution_h = buf.get_u16_le();
7252 __struct.resolution_v = buf.get_u16_le();
7253 __struct.cam_definition_version = buf.get_u16_le();
7254 for v in &mut __struct.vendor_name {
7255 let val = buf.get_u8();
7256 *v = val;
7257 }
7258 for v in &mut __struct.model_name {
7259 let val = buf.get_u8();
7260 *v = val;
7261 }
7262 __struct.lens_id = buf.get_u8();
7263 for v in &mut __struct.cam_definition_uri {
7264 let val = buf.get_u8();
7265 *v = val;
7266 }
7267 __struct.gimbal_device_id = buf.get_u8();
7268 __struct.camera_device_id = buf.get_u8();
7269 Ok(__struct)
7270 }
7271 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7272 let mut __tmp = BytesMut::new(bytes);
7273 #[allow(clippy::absurd_extreme_comparisons)]
7274 #[allow(unused_comparisons)]
7275 if __tmp.remaining() < Self::ENCODED_LEN {
7276 panic!(
7277 "buffer is too small (need {} bytes, but got {})",
7278 Self::ENCODED_LEN,
7279 __tmp.remaining(),
7280 )
7281 }
7282 __tmp.put_u32_le(self.time_boot_ms);
7283 __tmp.put_u32_le(self.firmware_version);
7284 __tmp.put_f32_le(self.focal_length);
7285 __tmp.put_f32_le(self.sensor_size_h);
7286 __tmp.put_f32_le(self.sensor_size_v);
7287 __tmp.put_u32_le(self.flags.bits());
7288 __tmp.put_u16_le(self.resolution_h);
7289 __tmp.put_u16_le(self.resolution_v);
7290 __tmp.put_u16_le(self.cam_definition_version);
7291 for val in &self.vendor_name {
7292 __tmp.put_u8(*val);
7293 }
7294 for val in &self.model_name {
7295 __tmp.put_u8(*val);
7296 }
7297 __tmp.put_u8(self.lens_id);
7298 for val in &self.cam_definition_uri {
7299 __tmp.put_u8(*val);
7300 }
7301 __tmp.put_u8(self.gimbal_device_id);
7302 __tmp.put_u8(self.camera_device_id);
7303 if matches!(version, MavlinkVersion::V2) {
7304 let len = __tmp.len();
7305 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7306 } else {
7307 __tmp.len()
7308 }
7309 }
7310}
7311#[doc = "id: 260"]
7312#[doc = "Settings of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
7313#[derive(Debug, Clone, PartialEq)]
7314#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7315#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7316pub struct CAMERA_SETTINGS_DATA {
7317 #[doc = "Timestamp (time since system boot)."]
7318 pub time_boot_ms: u32,
7319 #[doc = "Camera mode"]
7320 pub mode_id: CameraMode,
7321 #[doc = "Current zoom level as a percentage of the full range (0.0 to 100.0, NaN if not known)"]
7322 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7323 pub zoomLevel: f32,
7324 #[doc = "Current focus level as a percentage of the full range (0.0 to 100.0, NaN if not known)"]
7325 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7326 pub focusLevel: f32,
7327 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
7328 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7329 pub camera_device_id: u8,
7330}
7331impl CAMERA_SETTINGS_DATA {
7332 pub const ENCODED_LEN: usize = 14usize;
7333 pub const DEFAULT: Self = Self {
7334 time_boot_ms: 0_u32,
7335 mode_id: CameraMode::DEFAULT,
7336 zoomLevel: 0.0_f32,
7337 focusLevel: 0.0_f32,
7338 camera_device_id: 0_u8,
7339 };
7340 #[cfg(feature = "arbitrary")]
7341 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7342 use arbitrary::{Arbitrary, Unstructured};
7343 let mut buf = [0u8; 1024];
7344 rng.fill_bytes(&mut buf);
7345 let mut unstructured = Unstructured::new(&buf);
7346 Self::arbitrary(&mut unstructured).unwrap_or_default()
7347 }
7348}
7349impl Default for CAMERA_SETTINGS_DATA {
7350 fn default() -> Self {
7351 Self::DEFAULT.clone()
7352 }
7353}
7354impl MessageData for CAMERA_SETTINGS_DATA {
7355 type Message = MavMessage;
7356 const ID: u32 = 260u32;
7357 const NAME: &'static str = "CAMERA_SETTINGS";
7358 const EXTRA_CRC: u8 = 146u8;
7359 const ENCODED_LEN: usize = 14usize;
7360 fn deser(
7361 _version: MavlinkVersion,
7362 __input: &[u8],
7363 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7364 let avail_len = __input.len();
7365 let mut payload_buf = [0; Self::ENCODED_LEN];
7366 let mut buf = if avail_len < Self::ENCODED_LEN {
7367 payload_buf[0..avail_len].copy_from_slice(__input);
7368 Bytes::new(&payload_buf)
7369 } else {
7370 Bytes::new(__input)
7371 };
7372 let mut __struct = Self::default();
7373 __struct.time_boot_ms = buf.get_u32_le();
7374 let tmp = buf.get_u8();
7375 __struct.mode_id =
7376 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7377 enum_type: "CameraMode",
7378 value: tmp as u32,
7379 })?;
7380 __struct.zoomLevel = buf.get_f32_le();
7381 __struct.focusLevel = buf.get_f32_le();
7382 __struct.camera_device_id = buf.get_u8();
7383 Ok(__struct)
7384 }
7385 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7386 let mut __tmp = BytesMut::new(bytes);
7387 #[allow(clippy::absurd_extreme_comparisons)]
7388 #[allow(unused_comparisons)]
7389 if __tmp.remaining() < Self::ENCODED_LEN {
7390 panic!(
7391 "buffer is too small (need {} bytes, but got {})",
7392 Self::ENCODED_LEN,
7393 __tmp.remaining(),
7394 )
7395 }
7396 __tmp.put_u32_le(self.time_boot_ms);
7397 __tmp.put_u8(self.mode_id as u8);
7398 __tmp.put_f32_le(self.zoomLevel);
7399 __tmp.put_f32_le(self.focusLevel);
7400 __tmp.put_u8(self.camera_device_id);
7401 if matches!(version, MavlinkVersion::V2) {
7402 let len = __tmp.len();
7403 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7404 } else {
7405 __tmp.len()
7406 }
7407 }
7408}
7409#[doc = "id: 277"]
7410#[doc = "Camera absolute thermal range. This can be streamed when the associated VIDEO_STREAM_STATUS `flag` field bit VIDEO_STREAM_STATUS_FLAGS_THERMAL_RANGE_ENABLED is set, but a GCS may choose to only request it for the current active stream. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval (param3 indicates the stream id of the current camera, or 0 for all streams, param4 indicates the target camera_device_id for autopilot-attached cameras or 0 for MAVLink cameras)."]
7411#[derive(Debug, Clone, PartialEq)]
7412#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7413#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7414pub struct CAMERA_THERMAL_RANGE_DATA {
7415 #[doc = "Timestamp (time since system boot)."]
7416 pub time_boot_ms: u32,
7417 #[doc = "Temperature max."]
7418 pub max: f32,
7419 #[doc = "Temperature max point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown."]
7420 pub max_point_x: f32,
7421 #[doc = "Temperature max point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown."]
7422 pub max_point_y: f32,
7423 #[doc = "Temperature min."]
7424 pub min: f32,
7425 #[doc = "Temperature min point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown."]
7426 pub min_point_x: f32,
7427 #[doc = "Temperature min point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown."]
7428 pub min_point_y: f32,
7429 #[doc = "Video Stream ID (1 for first, 2 for second, etc.)"]
7430 pub stream_id: u8,
7431 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
7432 pub camera_device_id: u8,
7433}
7434impl CAMERA_THERMAL_RANGE_DATA {
7435 pub const ENCODED_LEN: usize = 30usize;
7436 pub const DEFAULT: Self = Self {
7437 time_boot_ms: 0_u32,
7438 max: 0.0_f32,
7439 max_point_x: 0.0_f32,
7440 max_point_y: 0.0_f32,
7441 min: 0.0_f32,
7442 min_point_x: 0.0_f32,
7443 min_point_y: 0.0_f32,
7444 stream_id: 0_u8,
7445 camera_device_id: 0_u8,
7446 };
7447 #[cfg(feature = "arbitrary")]
7448 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7449 use arbitrary::{Arbitrary, Unstructured};
7450 let mut buf = [0u8; 1024];
7451 rng.fill_bytes(&mut buf);
7452 let mut unstructured = Unstructured::new(&buf);
7453 Self::arbitrary(&mut unstructured).unwrap_or_default()
7454 }
7455}
7456impl Default for CAMERA_THERMAL_RANGE_DATA {
7457 fn default() -> Self {
7458 Self::DEFAULT.clone()
7459 }
7460}
7461impl MessageData for CAMERA_THERMAL_RANGE_DATA {
7462 type Message = MavMessage;
7463 const ID: u32 = 277u32;
7464 const NAME: &'static str = "CAMERA_THERMAL_RANGE";
7465 const EXTRA_CRC: u8 = 62u8;
7466 const ENCODED_LEN: usize = 30usize;
7467 fn deser(
7468 _version: MavlinkVersion,
7469 __input: &[u8],
7470 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7471 let avail_len = __input.len();
7472 let mut payload_buf = [0; Self::ENCODED_LEN];
7473 let mut buf = if avail_len < Self::ENCODED_LEN {
7474 payload_buf[0..avail_len].copy_from_slice(__input);
7475 Bytes::new(&payload_buf)
7476 } else {
7477 Bytes::new(__input)
7478 };
7479 let mut __struct = Self::default();
7480 __struct.time_boot_ms = buf.get_u32_le();
7481 __struct.max = buf.get_f32_le();
7482 __struct.max_point_x = buf.get_f32_le();
7483 __struct.max_point_y = buf.get_f32_le();
7484 __struct.min = buf.get_f32_le();
7485 __struct.min_point_x = buf.get_f32_le();
7486 __struct.min_point_y = buf.get_f32_le();
7487 __struct.stream_id = buf.get_u8();
7488 __struct.camera_device_id = buf.get_u8();
7489 Ok(__struct)
7490 }
7491 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7492 let mut __tmp = BytesMut::new(bytes);
7493 #[allow(clippy::absurd_extreme_comparisons)]
7494 #[allow(unused_comparisons)]
7495 if __tmp.remaining() < Self::ENCODED_LEN {
7496 panic!(
7497 "buffer is too small (need {} bytes, but got {})",
7498 Self::ENCODED_LEN,
7499 __tmp.remaining(),
7500 )
7501 }
7502 __tmp.put_u32_le(self.time_boot_ms);
7503 __tmp.put_f32_le(self.max);
7504 __tmp.put_f32_le(self.max_point_x);
7505 __tmp.put_f32_le(self.max_point_y);
7506 __tmp.put_f32_le(self.min);
7507 __tmp.put_f32_le(self.min_point_x);
7508 __tmp.put_f32_le(self.min_point_y);
7509 __tmp.put_u8(self.stream_id);
7510 __tmp.put_u8(self.camera_device_id);
7511 if matches!(version, MavlinkVersion::V2) {
7512 let len = __tmp.len();
7513 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7514 } else {
7515 __tmp.len()
7516 }
7517 }
7518}
7519#[doc = "id: 276"]
7520#[doc = "Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval."]
7521#[derive(Debug, Clone, PartialEq)]
7522#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7523#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7524pub struct CAMERA_TRACKING_GEO_STATUS_DATA {
7525 #[doc = "Latitude of tracked object"]
7526 pub lat: i32,
7527 #[doc = "Longitude of tracked object"]
7528 pub lon: i32,
7529 #[doc = "Altitude of tracked object(AMSL, WGS84)"]
7530 pub alt: f32,
7531 #[doc = "Horizontal accuracy. NAN if unknown"]
7532 pub h_acc: f32,
7533 #[doc = "Vertical accuracy. NAN if unknown"]
7534 pub v_acc: f32,
7535 #[doc = "North velocity of tracked object. NAN if unknown"]
7536 pub vel_n: f32,
7537 #[doc = "East velocity of tracked object. NAN if unknown"]
7538 pub vel_e: f32,
7539 #[doc = "Down velocity of tracked object. NAN if unknown"]
7540 pub vel_d: f32,
7541 #[doc = "Velocity accuracy. NAN if unknown"]
7542 pub vel_acc: f32,
7543 #[doc = "Distance between camera and tracked object. NAN if unknown"]
7544 pub dist: f32,
7545 #[doc = "Heading in radians, in NED. NAN if unknown"]
7546 pub hdg: f32,
7547 #[doc = "Accuracy of heading, in NED. NAN if unknown"]
7548 pub hdg_acc: f32,
7549 #[doc = "Current tracking status"]
7550 pub tracking_status: CameraTrackingStatusFlags,
7551 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
7552 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7553 pub camera_device_id: u8,
7554}
7555impl CAMERA_TRACKING_GEO_STATUS_DATA {
7556 pub const ENCODED_LEN: usize = 50usize;
7557 pub const DEFAULT: Self = Self {
7558 lat: 0_i32,
7559 lon: 0_i32,
7560 alt: 0.0_f32,
7561 h_acc: 0.0_f32,
7562 v_acc: 0.0_f32,
7563 vel_n: 0.0_f32,
7564 vel_e: 0.0_f32,
7565 vel_d: 0.0_f32,
7566 vel_acc: 0.0_f32,
7567 dist: 0.0_f32,
7568 hdg: 0.0_f32,
7569 hdg_acc: 0.0_f32,
7570 tracking_status: CameraTrackingStatusFlags::DEFAULT,
7571 camera_device_id: 0_u8,
7572 };
7573 #[cfg(feature = "arbitrary")]
7574 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7575 use arbitrary::{Arbitrary, Unstructured};
7576 let mut buf = [0u8; 1024];
7577 rng.fill_bytes(&mut buf);
7578 let mut unstructured = Unstructured::new(&buf);
7579 Self::arbitrary(&mut unstructured).unwrap_or_default()
7580 }
7581}
7582impl Default for CAMERA_TRACKING_GEO_STATUS_DATA {
7583 fn default() -> Self {
7584 Self::DEFAULT.clone()
7585 }
7586}
7587impl MessageData for CAMERA_TRACKING_GEO_STATUS_DATA {
7588 type Message = MavMessage;
7589 const ID: u32 = 276u32;
7590 const NAME: &'static str = "CAMERA_TRACKING_GEO_STATUS";
7591 const EXTRA_CRC: u8 = 18u8;
7592 const ENCODED_LEN: usize = 50usize;
7593 fn deser(
7594 _version: MavlinkVersion,
7595 __input: &[u8],
7596 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7597 let avail_len = __input.len();
7598 let mut payload_buf = [0; Self::ENCODED_LEN];
7599 let mut buf = if avail_len < Self::ENCODED_LEN {
7600 payload_buf[0..avail_len].copy_from_slice(__input);
7601 Bytes::new(&payload_buf)
7602 } else {
7603 Bytes::new(__input)
7604 };
7605 let mut __struct = Self::default();
7606 __struct.lat = buf.get_i32_le();
7607 __struct.lon = buf.get_i32_le();
7608 __struct.alt = buf.get_f32_le();
7609 __struct.h_acc = buf.get_f32_le();
7610 __struct.v_acc = buf.get_f32_le();
7611 __struct.vel_n = buf.get_f32_le();
7612 __struct.vel_e = buf.get_f32_le();
7613 __struct.vel_d = buf.get_f32_le();
7614 __struct.vel_acc = buf.get_f32_le();
7615 __struct.dist = buf.get_f32_le();
7616 __struct.hdg = buf.get_f32_le();
7617 __struct.hdg_acc = buf.get_f32_le();
7618 let tmp = buf.get_u8();
7619 __struct.tracking_status =
7620 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7621 enum_type: "CameraTrackingStatusFlags",
7622 value: tmp as u32,
7623 })?;
7624 __struct.camera_device_id = buf.get_u8();
7625 Ok(__struct)
7626 }
7627 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7628 let mut __tmp = BytesMut::new(bytes);
7629 #[allow(clippy::absurd_extreme_comparisons)]
7630 #[allow(unused_comparisons)]
7631 if __tmp.remaining() < Self::ENCODED_LEN {
7632 panic!(
7633 "buffer is too small (need {} bytes, but got {})",
7634 Self::ENCODED_LEN,
7635 __tmp.remaining(),
7636 )
7637 }
7638 __tmp.put_i32_le(self.lat);
7639 __tmp.put_i32_le(self.lon);
7640 __tmp.put_f32_le(self.alt);
7641 __tmp.put_f32_le(self.h_acc);
7642 __tmp.put_f32_le(self.v_acc);
7643 __tmp.put_f32_le(self.vel_n);
7644 __tmp.put_f32_le(self.vel_e);
7645 __tmp.put_f32_le(self.vel_d);
7646 __tmp.put_f32_le(self.vel_acc);
7647 __tmp.put_f32_le(self.dist);
7648 __tmp.put_f32_le(self.hdg);
7649 __tmp.put_f32_le(self.hdg_acc);
7650 __tmp.put_u8(self.tracking_status as u8);
7651 __tmp.put_u8(self.camera_device_id);
7652 if matches!(version, MavlinkVersion::V2) {
7653 let len = __tmp.len();
7654 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7655 } else {
7656 __tmp.len()
7657 }
7658 }
7659}
7660#[doc = "id: 275"]
7661#[doc = "Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval."]
7662#[derive(Debug, Clone, PartialEq)]
7663#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7664#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7665pub struct CAMERA_TRACKING_IMAGE_STATUS_DATA {
7666 #[doc = "Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown"]
7667 pub point_x: f32,
7668 #[doc = "Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown"]
7669 pub point_y: f32,
7670 #[doc = "Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown"]
7671 pub radius: f32,
7672 #[doc = "Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown"]
7673 pub rec_top_x: f32,
7674 #[doc = "Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown"]
7675 pub rec_top_y: f32,
7676 #[doc = "Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown"]
7677 pub rec_bottom_x: f32,
7678 #[doc = "Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown"]
7679 pub rec_bottom_y: f32,
7680 #[doc = "Current tracking status"]
7681 pub tracking_status: CameraTrackingStatusFlags,
7682 #[doc = "Current tracking mode"]
7683 pub tracking_mode: CameraTrackingMode,
7684 #[doc = "Defines location of target data"]
7685 pub target_data: CameraTrackingTargetData,
7686 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
7687 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7688 pub camera_device_id: u8,
7689}
7690impl CAMERA_TRACKING_IMAGE_STATUS_DATA {
7691 pub const ENCODED_LEN: usize = 32usize;
7692 pub const DEFAULT: Self = Self {
7693 point_x: 0.0_f32,
7694 point_y: 0.0_f32,
7695 radius: 0.0_f32,
7696 rec_top_x: 0.0_f32,
7697 rec_top_y: 0.0_f32,
7698 rec_bottom_x: 0.0_f32,
7699 rec_bottom_y: 0.0_f32,
7700 tracking_status: CameraTrackingStatusFlags::DEFAULT,
7701 tracking_mode: CameraTrackingMode::DEFAULT,
7702 target_data: CameraTrackingTargetData::DEFAULT,
7703 camera_device_id: 0_u8,
7704 };
7705 #[cfg(feature = "arbitrary")]
7706 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7707 use arbitrary::{Arbitrary, Unstructured};
7708 let mut buf = [0u8; 1024];
7709 rng.fill_bytes(&mut buf);
7710 let mut unstructured = Unstructured::new(&buf);
7711 Self::arbitrary(&mut unstructured).unwrap_or_default()
7712 }
7713}
7714impl Default for CAMERA_TRACKING_IMAGE_STATUS_DATA {
7715 fn default() -> Self {
7716 Self::DEFAULT.clone()
7717 }
7718}
7719impl MessageData for CAMERA_TRACKING_IMAGE_STATUS_DATA {
7720 type Message = MavMessage;
7721 const ID: u32 = 275u32;
7722 const NAME: &'static str = "CAMERA_TRACKING_IMAGE_STATUS";
7723 const EXTRA_CRC: u8 = 126u8;
7724 const ENCODED_LEN: usize = 32usize;
7725 fn deser(
7726 _version: MavlinkVersion,
7727 __input: &[u8],
7728 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7729 let avail_len = __input.len();
7730 let mut payload_buf = [0; Self::ENCODED_LEN];
7731 let mut buf = if avail_len < Self::ENCODED_LEN {
7732 payload_buf[0..avail_len].copy_from_slice(__input);
7733 Bytes::new(&payload_buf)
7734 } else {
7735 Bytes::new(__input)
7736 };
7737 let mut __struct = Self::default();
7738 __struct.point_x = buf.get_f32_le();
7739 __struct.point_y = buf.get_f32_le();
7740 __struct.radius = buf.get_f32_le();
7741 __struct.rec_top_x = buf.get_f32_le();
7742 __struct.rec_top_y = buf.get_f32_le();
7743 __struct.rec_bottom_x = buf.get_f32_le();
7744 __struct.rec_bottom_y = buf.get_f32_le();
7745 let tmp = buf.get_u8();
7746 __struct.tracking_status =
7747 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7748 enum_type: "CameraTrackingStatusFlags",
7749 value: tmp as u32,
7750 })?;
7751 let tmp = buf.get_u8();
7752 __struct.tracking_mode =
7753 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7754 enum_type: "CameraTrackingMode",
7755 value: tmp as u32,
7756 })?;
7757 let tmp = buf.get_u8();
7758 __struct.target_data =
7759 CameraTrackingTargetData::from_bits(tmp & CameraTrackingTargetData::all().bits())
7760 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
7761 flag_type: "CameraTrackingTargetData",
7762 value: tmp as u32,
7763 })?;
7764 __struct.camera_device_id = buf.get_u8();
7765 Ok(__struct)
7766 }
7767 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7768 let mut __tmp = BytesMut::new(bytes);
7769 #[allow(clippy::absurd_extreme_comparisons)]
7770 #[allow(unused_comparisons)]
7771 if __tmp.remaining() < Self::ENCODED_LEN {
7772 panic!(
7773 "buffer is too small (need {} bytes, but got {})",
7774 Self::ENCODED_LEN,
7775 __tmp.remaining(),
7776 )
7777 }
7778 __tmp.put_f32_le(self.point_x);
7779 __tmp.put_f32_le(self.point_y);
7780 __tmp.put_f32_le(self.radius);
7781 __tmp.put_f32_le(self.rec_top_x);
7782 __tmp.put_f32_le(self.rec_top_y);
7783 __tmp.put_f32_le(self.rec_bottom_x);
7784 __tmp.put_f32_le(self.rec_bottom_y);
7785 __tmp.put_u8(self.tracking_status as u8);
7786 __tmp.put_u8(self.tracking_mode as u8);
7787 __tmp.put_u8(self.target_data.bits());
7788 __tmp.put_u8(self.camera_device_id);
7789 if matches!(version, MavlinkVersion::V2) {
7790 let len = __tmp.len();
7791 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7792 } else {
7793 __tmp.len()
7794 }
7795 }
7796}
7797#[doc = "id: 112"]
7798#[doc = "Camera-IMU triggering and synchronisation message."]
7799#[derive(Debug, Clone, PartialEq)]
7800#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7801#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7802pub struct CAMERA_TRIGGER_DATA {
7803 #[doc = "Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
7804 pub time_usec: u64,
7805 #[doc = "Image frame sequence"]
7806 pub seq: u32,
7807}
7808impl CAMERA_TRIGGER_DATA {
7809 pub const ENCODED_LEN: usize = 12usize;
7810 pub const DEFAULT: Self = Self {
7811 time_usec: 0_u64,
7812 seq: 0_u32,
7813 };
7814 #[cfg(feature = "arbitrary")]
7815 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7816 use arbitrary::{Arbitrary, Unstructured};
7817 let mut buf = [0u8; 1024];
7818 rng.fill_bytes(&mut buf);
7819 let mut unstructured = Unstructured::new(&buf);
7820 Self::arbitrary(&mut unstructured).unwrap_or_default()
7821 }
7822}
7823impl Default for CAMERA_TRIGGER_DATA {
7824 fn default() -> Self {
7825 Self::DEFAULT.clone()
7826 }
7827}
7828impl MessageData for CAMERA_TRIGGER_DATA {
7829 type Message = MavMessage;
7830 const ID: u32 = 112u32;
7831 const NAME: &'static str = "CAMERA_TRIGGER";
7832 const EXTRA_CRC: u8 = 174u8;
7833 const ENCODED_LEN: usize = 12usize;
7834 fn deser(
7835 _version: MavlinkVersion,
7836 __input: &[u8],
7837 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7838 let avail_len = __input.len();
7839 let mut payload_buf = [0; Self::ENCODED_LEN];
7840 let mut buf = if avail_len < Self::ENCODED_LEN {
7841 payload_buf[0..avail_len].copy_from_slice(__input);
7842 Bytes::new(&payload_buf)
7843 } else {
7844 Bytes::new(__input)
7845 };
7846 let mut __struct = Self::default();
7847 __struct.time_usec = buf.get_u64_le();
7848 __struct.seq = buf.get_u32_le();
7849 Ok(__struct)
7850 }
7851 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7852 let mut __tmp = BytesMut::new(bytes);
7853 #[allow(clippy::absurd_extreme_comparisons)]
7854 #[allow(unused_comparisons)]
7855 if __tmp.remaining() < Self::ENCODED_LEN {
7856 panic!(
7857 "buffer is too small (need {} bytes, but got {})",
7858 Self::ENCODED_LEN,
7859 __tmp.remaining(),
7860 )
7861 }
7862 __tmp.put_u64_le(self.time_usec);
7863 __tmp.put_u32_le(self.seq);
7864 if matches!(version, MavlinkVersion::V2) {
7865 let len = __tmp.len();
7866 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7867 } else {
7868 __tmp.len()
7869 }
7870 }
7871}
7872#[doc = "id: 387"]
7873#[doc = "A forwarded CANFD frame as requested by MAV_CMD_CAN_FORWARD. These are separated from CAN_FRAME as they need different handling (eg. TAO handling)."]
7874#[derive(Debug, Clone, PartialEq)]
7875#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7876#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7877pub struct CANFD_FRAME_DATA {
7878 #[doc = "Frame ID"]
7879 pub id: u32,
7880 #[doc = "System ID."]
7881 pub target_system: u8,
7882 #[doc = "Component ID."]
7883 pub target_component: u8,
7884 #[doc = "bus number"]
7885 pub bus: u8,
7886 #[doc = "Frame length"]
7887 pub len: u8,
7888 #[doc = "Frame data"]
7889 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7890 pub data: [u8; 64],
7891}
7892impl CANFD_FRAME_DATA {
7893 pub const ENCODED_LEN: usize = 72usize;
7894 pub const DEFAULT: Self = Self {
7895 id: 0_u32,
7896 target_system: 0_u8,
7897 target_component: 0_u8,
7898 bus: 0_u8,
7899 len: 0_u8,
7900 data: [0_u8; 64usize],
7901 };
7902 #[cfg(feature = "arbitrary")]
7903 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7904 use arbitrary::{Arbitrary, Unstructured};
7905 let mut buf = [0u8; 1024];
7906 rng.fill_bytes(&mut buf);
7907 let mut unstructured = Unstructured::new(&buf);
7908 Self::arbitrary(&mut unstructured).unwrap_or_default()
7909 }
7910}
7911impl Default for CANFD_FRAME_DATA {
7912 fn default() -> Self {
7913 Self::DEFAULT.clone()
7914 }
7915}
7916impl MessageData for CANFD_FRAME_DATA {
7917 type Message = MavMessage;
7918 const ID: u32 = 387u32;
7919 const NAME: &'static str = "CANFD_FRAME";
7920 const EXTRA_CRC: u8 = 4u8;
7921 const ENCODED_LEN: usize = 72usize;
7922 fn deser(
7923 _version: MavlinkVersion,
7924 __input: &[u8],
7925 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7926 let avail_len = __input.len();
7927 let mut payload_buf = [0; Self::ENCODED_LEN];
7928 let mut buf = if avail_len < Self::ENCODED_LEN {
7929 payload_buf[0..avail_len].copy_from_slice(__input);
7930 Bytes::new(&payload_buf)
7931 } else {
7932 Bytes::new(__input)
7933 };
7934 let mut __struct = Self::default();
7935 __struct.id = buf.get_u32_le();
7936 __struct.target_system = buf.get_u8();
7937 __struct.target_component = buf.get_u8();
7938 __struct.bus = buf.get_u8();
7939 __struct.len = buf.get_u8();
7940 for v in &mut __struct.data {
7941 let val = buf.get_u8();
7942 *v = val;
7943 }
7944 Ok(__struct)
7945 }
7946 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7947 let mut __tmp = BytesMut::new(bytes);
7948 #[allow(clippy::absurd_extreme_comparisons)]
7949 #[allow(unused_comparisons)]
7950 if __tmp.remaining() < Self::ENCODED_LEN {
7951 panic!(
7952 "buffer is too small (need {} bytes, but got {})",
7953 Self::ENCODED_LEN,
7954 __tmp.remaining(),
7955 )
7956 }
7957 __tmp.put_u32_le(self.id);
7958 __tmp.put_u8(self.target_system);
7959 __tmp.put_u8(self.target_component);
7960 __tmp.put_u8(self.bus);
7961 __tmp.put_u8(self.len);
7962 for val in &self.data {
7963 __tmp.put_u8(*val);
7964 }
7965 if matches!(version, MavlinkVersion::V2) {
7966 let len = __tmp.len();
7967 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7968 } else {
7969 __tmp.len()
7970 }
7971 }
7972}
7973#[doc = "id: 388"]
7974#[doc = "Modify the filter of what CAN messages to forward over the mavlink. This can be used to make CAN forwarding work well on low bandwidth links. The filtering is applied on bits 8 to 24 of the CAN id (2nd and 3rd bytes) which corresponds to the DroneCAN message ID for DroneCAN. Filters with more than 16 IDs can be constructed by sending multiple CAN_FILTER_MODIFY messages."]
7975#[derive(Debug, Clone, PartialEq)]
7976#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7977#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7978pub struct CAN_FILTER_MODIFY_DATA {
7979 #[doc = "filter IDs, length num_ids"]
7980 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7981 pub ids: [u16; 16],
7982 #[doc = "System ID."]
7983 pub target_system: u8,
7984 #[doc = "Component ID."]
7985 pub target_component: u8,
7986 #[doc = "bus number"]
7987 pub bus: u8,
7988 #[doc = "what operation to perform on the filter list. See CAN_FILTER_OP enum."]
7989 pub operation: CanFilterOp,
7990 #[doc = "number of IDs in filter list"]
7991 pub num_ids: u8,
7992}
7993impl CAN_FILTER_MODIFY_DATA {
7994 pub const ENCODED_LEN: usize = 37usize;
7995 pub const DEFAULT: Self = Self {
7996 ids: [0_u16; 16usize],
7997 target_system: 0_u8,
7998 target_component: 0_u8,
7999 bus: 0_u8,
8000 operation: CanFilterOp::DEFAULT,
8001 num_ids: 0_u8,
8002 };
8003 #[cfg(feature = "arbitrary")]
8004 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8005 use arbitrary::{Arbitrary, Unstructured};
8006 let mut buf = [0u8; 1024];
8007 rng.fill_bytes(&mut buf);
8008 let mut unstructured = Unstructured::new(&buf);
8009 Self::arbitrary(&mut unstructured).unwrap_or_default()
8010 }
8011}
8012impl Default for CAN_FILTER_MODIFY_DATA {
8013 fn default() -> Self {
8014 Self::DEFAULT.clone()
8015 }
8016}
8017impl MessageData for CAN_FILTER_MODIFY_DATA {
8018 type Message = MavMessage;
8019 const ID: u32 = 388u32;
8020 const NAME: &'static str = "CAN_FILTER_MODIFY";
8021 const EXTRA_CRC: u8 = 8u8;
8022 const ENCODED_LEN: usize = 37usize;
8023 fn deser(
8024 _version: MavlinkVersion,
8025 __input: &[u8],
8026 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8027 let avail_len = __input.len();
8028 let mut payload_buf = [0; Self::ENCODED_LEN];
8029 let mut buf = if avail_len < Self::ENCODED_LEN {
8030 payload_buf[0..avail_len].copy_from_slice(__input);
8031 Bytes::new(&payload_buf)
8032 } else {
8033 Bytes::new(__input)
8034 };
8035 let mut __struct = Self::default();
8036 for v in &mut __struct.ids {
8037 let val = buf.get_u16_le();
8038 *v = val;
8039 }
8040 __struct.target_system = buf.get_u8();
8041 __struct.target_component = buf.get_u8();
8042 __struct.bus = buf.get_u8();
8043 let tmp = buf.get_u8();
8044 __struct.operation =
8045 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8046 enum_type: "CanFilterOp",
8047 value: tmp as u32,
8048 })?;
8049 __struct.num_ids = buf.get_u8();
8050 Ok(__struct)
8051 }
8052 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8053 let mut __tmp = BytesMut::new(bytes);
8054 #[allow(clippy::absurd_extreme_comparisons)]
8055 #[allow(unused_comparisons)]
8056 if __tmp.remaining() < Self::ENCODED_LEN {
8057 panic!(
8058 "buffer is too small (need {} bytes, but got {})",
8059 Self::ENCODED_LEN,
8060 __tmp.remaining(),
8061 )
8062 }
8063 for val in &self.ids {
8064 __tmp.put_u16_le(*val);
8065 }
8066 __tmp.put_u8(self.target_system);
8067 __tmp.put_u8(self.target_component);
8068 __tmp.put_u8(self.bus);
8069 __tmp.put_u8(self.operation as u8);
8070 __tmp.put_u8(self.num_ids);
8071 if matches!(version, MavlinkVersion::V2) {
8072 let len = __tmp.len();
8073 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8074 } else {
8075 __tmp.len()
8076 }
8077 }
8078}
8079#[doc = "id: 386"]
8080#[doc = "A forwarded CAN frame as requested by MAV_CMD_CAN_FORWARD."]
8081#[derive(Debug, Clone, PartialEq)]
8082#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8083#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8084pub struct CAN_FRAME_DATA {
8085 #[doc = "Frame ID"]
8086 pub id: u32,
8087 #[doc = "System ID."]
8088 pub target_system: u8,
8089 #[doc = "Component ID."]
8090 pub target_component: u8,
8091 #[doc = "Bus number"]
8092 pub bus: u8,
8093 #[doc = "Frame length"]
8094 pub len: u8,
8095 #[doc = "Frame data"]
8096 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8097 pub data: [u8; 8],
8098}
8099impl CAN_FRAME_DATA {
8100 pub const ENCODED_LEN: usize = 16usize;
8101 pub const DEFAULT: Self = Self {
8102 id: 0_u32,
8103 target_system: 0_u8,
8104 target_component: 0_u8,
8105 bus: 0_u8,
8106 len: 0_u8,
8107 data: [0_u8; 8usize],
8108 };
8109 #[cfg(feature = "arbitrary")]
8110 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8111 use arbitrary::{Arbitrary, Unstructured};
8112 let mut buf = [0u8; 1024];
8113 rng.fill_bytes(&mut buf);
8114 let mut unstructured = Unstructured::new(&buf);
8115 Self::arbitrary(&mut unstructured).unwrap_or_default()
8116 }
8117}
8118impl Default for CAN_FRAME_DATA {
8119 fn default() -> Self {
8120 Self::DEFAULT.clone()
8121 }
8122}
8123impl MessageData for CAN_FRAME_DATA {
8124 type Message = MavMessage;
8125 const ID: u32 = 386u32;
8126 const NAME: &'static str = "CAN_FRAME";
8127 const EXTRA_CRC: u8 = 132u8;
8128 const ENCODED_LEN: usize = 16usize;
8129 fn deser(
8130 _version: MavlinkVersion,
8131 __input: &[u8],
8132 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8133 let avail_len = __input.len();
8134 let mut payload_buf = [0; Self::ENCODED_LEN];
8135 let mut buf = if avail_len < Self::ENCODED_LEN {
8136 payload_buf[0..avail_len].copy_from_slice(__input);
8137 Bytes::new(&payload_buf)
8138 } else {
8139 Bytes::new(__input)
8140 };
8141 let mut __struct = Self::default();
8142 __struct.id = buf.get_u32_le();
8143 __struct.target_system = buf.get_u8();
8144 __struct.target_component = buf.get_u8();
8145 __struct.bus = buf.get_u8();
8146 __struct.len = buf.get_u8();
8147 for v in &mut __struct.data {
8148 let val = buf.get_u8();
8149 *v = val;
8150 }
8151 Ok(__struct)
8152 }
8153 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8154 let mut __tmp = BytesMut::new(bytes);
8155 #[allow(clippy::absurd_extreme_comparisons)]
8156 #[allow(unused_comparisons)]
8157 if __tmp.remaining() < Self::ENCODED_LEN {
8158 panic!(
8159 "buffer is too small (need {} bytes, but got {})",
8160 Self::ENCODED_LEN,
8161 __tmp.remaining(),
8162 )
8163 }
8164 __tmp.put_u32_le(self.id);
8165 __tmp.put_u8(self.target_system);
8166 __tmp.put_u8(self.target_component);
8167 __tmp.put_u8(self.bus);
8168 __tmp.put_u8(self.len);
8169 for val in &self.data {
8170 __tmp.put_u8(*val);
8171 }
8172 if matches!(version, MavlinkVersion::V2) {
8173 let len = __tmp.len();
8174 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8175 } else {
8176 __tmp.len()
8177 }
8178 }
8179}
8180#[doc = "id: 336"]
8181#[doc = "Configure cellular modems. This message is re-emitted as an acknowledgement by the modem. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE."]
8182#[derive(Debug, Clone, PartialEq)]
8183#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8184#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8185pub struct CELLULAR_CONFIG_DATA {
8186 #[doc = "Enable/disable LTE. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response."]
8187 pub enable_lte: u8,
8188 #[doc = "Enable/disable PIN on the SIM card. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response."]
8189 pub enable_pin: u8,
8190 #[doc = "PIN sent to the SIM card. Blank when PIN is disabled. Empty when message is sent back as a response."]
8191 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8192 pub pin: [u8; 16],
8193 #[doc = "New PIN when changing the PIN. Blank to leave it unchanged. Empty when message is sent back as a response."]
8194 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8195 pub new_pin: [u8; 16],
8196 #[doc = "Name of the cellular APN. Blank to leave it unchanged. Current APN when sent back as a response."]
8197 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8198 pub apn: [u8; 32],
8199 #[doc = "Required PUK code in case the user failed to authenticate 3 times with the PIN. Empty when message is sent back as a response."]
8200 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8201 pub puk: [u8; 16],
8202 #[doc = "Enable/disable roaming. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response."]
8203 pub roaming: u8,
8204 #[doc = "Message acceptance response (sent back to GS)."]
8205 pub response: CellularConfigResponse,
8206}
8207impl CELLULAR_CONFIG_DATA {
8208 pub const ENCODED_LEN: usize = 84usize;
8209 pub const DEFAULT: Self = Self {
8210 enable_lte: 0_u8,
8211 enable_pin: 0_u8,
8212 pin: [0_u8; 16usize],
8213 new_pin: [0_u8; 16usize],
8214 apn: [0_u8; 32usize],
8215 puk: [0_u8; 16usize],
8216 roaming: 0_u8,
8217 response: CellularConfigResponse::DEFAULT,
8218 };
8219 #[cfg(feature = "arbitrary")]
8220 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8221 use arbitrary::{Arbitrary, Unstructured};
8222 let mut buf = [0u8; 1024];
8223 rng.fill_bytes(&mut buf);
8224 let mut unstructured = Unstructured::new(&buf);
8225 Self::arbitrary(&mut unstructured).unwrap_or_default()
8226 }
8227}
8228impl Default for CELLULAR_CONFIG_DATA {
8229 fn default() -> Self {
8230 Self::DEFAULT.clone()
8231 }
8232}
8233impl MessageData for CELLULAR_CONFIG_DATA {
8234 type Message = MavMessage;
8235 const ID: u32 = 336u32;
8236 const NAME: &'static str = "CELLULAR_CONFIG";
8237 const EXTRA_CRC: u8 = 245u8;
8238 const ENCODED_LEN: usize = 84usize;
8239 fn deser(
8240 _version: MavlinkVersion,
8241 __input: &[u8],
8242 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8243 let avail_len = __input.len();
8244 let mut payload_buf = [0; Self::ENCODED_LEN];
8245 let mut buf = if avail_len < Self::ENCODED_LEN {
8246 payload_buf[0..avail_len].copy_from_slice(__input);
8247 Bytes::new(&payload_buf)
8248 } else {
8249 Bytes::new(__input)
8250 };
8251 let mut __struct = Self::default();
8252 __struct.enable_lte = buf.get_u8();
8253 __struct.enable_pin = buf.get_u8();
8254 for v in &mut __struct.pin {
8255 let val = buf.get_u8();
8256 *v = val;
8257 }
8258 for v in &mut __struct.new_pin {
8259 let val = buf.get_u8();
8260 *v = val;
8261 }
8262 for v in &mut __struct.apn {
8263 let val = buf.get_u8();
8264 *v = val;
8265 }
8266 for v in &mut __struct.puk {
8267 let val = buf.get_u8();
8268 *v = val;
8269 }
8270 __struct.roaming = buf.get_u8();
8271 let tmp = buf.get_u8();
8272 __struct.response =
8273 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8274 enum_type: "CellularConfigResponse",
8275 value: tmp as u32,
8276 })?;
8277 Ok(__struct)
8278 }
8279 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8280 let mut __tmp = BytesMut::new(bytes);
8281 #[allow(clippy::absurd_extreme_comparisons)]
8282 #[allow(unused_comparisons)]
8283 if __tmp.remaining() < Self::ENCODED_LEN {
8284 panic!(
8285 "buffer is too small (need {} bytes, but got {})",
8286 Self::ENCODED_LEN,
8287 __tmp.remaining(),
8288 )
8289 }
8290 __tmp.put_u8(self.enable_lte);
8291 __tmp.put_u8(self.enable_pin);
8292 for val in &self.pin {
8293 __tmp.put_u8(*val);
8294 }
8295 for val in &self.new_pin {
8296 __tmp.put_u8(*val);
8297 }
8298 for val in &self.apn {
8299 __tmp.put_u8(*val);
8300 }
8301 for val in &self.puk {
8302 __tmp.put_u8(*val);
8303 }
8304 __tmp.put_u8(self.roaming);
8305 __tmp.put_u8(self.response as u8);
8306 if matches!(version, MavlinkVersion::V2) {
8307 let len = __tmp.len();
8308 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8309 } else {
8310 __tmp.len()
8311 }
8312 }
8313}
8314#[doc = "id: 334"]
8315#[doc = "Report current used cellular network status."]
8316#[derive(Debug, Clone, PartialEq)]
8317#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8318#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8319pub struct CELLULAR_STATUS_DATA {
8320 #[doc = "Mobile country code. If unknown, set to UINT16_MAX"]
8321 pub mcc: u16,
8322 #[doc = "Mobile network code. If unknown, set to UINT16_MAX"]
8323 pub mnc: u16,
8324 #[doc = "Location area code. If unknown, set to 0"]
8325 pub lac: u16,
8326 #[doc = "Cellular modem status"]
8327 pub status: CellularStatusFlag,
8328 #[doc = "Failure reason when status in in CELLULAR_STATUS_FLAG_FAILED"]
8329 pub failure_reason: CellularNetworkFailedReason,
8330 #[doc = "Cellular network radio type: gsm, cdma, lte..."]
8331 pub mavtype: CellularNetworkRadioType,
8332 #[doc = "Signal quality in percent. If unknown, set to UINT8_MAX"]
8333 pub quality: u8,
8334}
8335impl CELLULAR_STATUS_DATA {
8336 pub const ENCODED_LEN: usize = 10usize;
8337 pub const DEFAULT: Self = Self {
8338 mcc: 0_u16,
8339 mnc: 0_u16,
8340 lac: 0_u16,
8341 status: CellularStatusFlag::DEFAULT,
8342 failure_reason: CellularNetworkFailedReason::DEFAULT,
8343 mavtype: CellularNetworkRadioType::DEFAULT,
8344 quality: 0_u8,
8345 };
8346 #[cfg(feature = "arbitrary")]
8347 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8348 use arbitrary::{Arbitrary, Unstructured};
8349 let mut buf = [0u8; 1024];
8350 rng.fill_bytes(&mut buf);
8351 let mut unstructured = Unstructured::new(&buf);
8352 Self::arbitrary(&mut unstructured).unwrap_or_default()
8353 }
8354}
8355impl Default for CELLULAR_STATUS_DATA {
8356 fn default() -> Self {
8357 Self::DEFAULT.clone()
8358 }
8359}
8360impl MessageData for CELLULAR_STATUS_DATA {
8361 type Message = MavMessage;
8362 const ID: u32 = 334u32;
8363 const NAME: &'static str = "CELLULAR_STATUS";
8364 const EXTRA_CRC: u8 = 72u8;
8365 const ENCODED_LEN: usize = 10usize;
8366 fn deser(
8367 _version: MavlinkVersion,
8368 __input: &[u8],
8369 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8370 let avail_len = __input.len();
8371 let mut payload_buf = [0; Self::ENCODED_LEN];
8372 let mut buf = if avail_len < Self::ENCODED_LEN {
8373 payload_buf[0..avail_len].copy_from_slice(__input);
8374 Bytes::new(&payload_buf)
8375 } else {
8376 Bytes::new(__input)
8377 };
8378 let mut __struct = Self::default();
8379 __struct.mcc = buf.get_u16_le();
8380 __struct.mnc = buf.get_u16_le();
8381 __struct.lac = buf.get_u16_le();
8382 let tmp = buf.get_u8();
8383 __struct.status =
8384 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8385 enum_type: "CellularStatusFlag",
8386 value: tmp as u32,
8387 })?;
8388 let tmp = buf.get_u8();
8389 __struct.failure_reason =
8390 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8391 enum_type: "CellularNetworkFailedReason",
8392 value: tmp as u32,
8393 })?;
8394 let tmp = buf.get_u8();
8395 __struct.mavtype =
8396 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8397 enum_type: "CellularNetworkRadioType",
8398 value: tmp as u32,
8399 })?;
8400 __struct.quality = buf.get_u8();
8401 Ok(__struct)
8402 }
8403 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8404 let mut __tmp = BytesMut::new(bytes);
8405 #[allow(clippy::absurd_extreme_comparisons)]
8406 #[allow(unused_comparisons)]
8407 if __tmp.remaining() < Self::ENCODED_LEN {
8408 panic!(
8409 "buffer is too small (need {} bytes, but got {})",
8410 Self::ENCODED_LEN,
8411 __tmp.remaining(),
8412 )
8413 }
8414 __tmp.put_u16_le(self.mcc);
8415 __tmp.put_u16_le(self.mnc);
8416 __tmp.put_u16_le(self.lac);
8417 __tmp.put_u8(self.status as u8);
8418 __tmp.put_u8(self.failure_reason as u8);
8419 __tmp.put_u8(self.mavtype as u8);
8420 __tmp.put_u8(self.quality);
8421 if matches!(version, MavlinkVersion::V2) {
8422 let len = __tmp.len();
8423 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8424 } else {
8425 __tmp.len()
8426 }
8427 }
8428}
8429#[doc = "id: 5"]
8430#[doc = "Request to control this MAV."]
8431#[derive(Debug, Clone, PartialEq)]
8432#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8433#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8434pub struct CHANGE_OPERATOR_CONTROL_DATA {
8435 #[doc = "System the GCS requests control for"]
8436 pub target_system: u8,
8437 #[doc = "0: request control of this MAV, 1: Release control of this MAV"]
8438 pub control_request: u8,
8439 #[doc = "0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch."]
8440 pub version: u8,
8441 #[doc = "Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and \"!?,.-\""]
8442 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8443 pub passkey: [u8; 25],
8444}
8445impl CHANGE_OPERATOR_CONTROL_DATA {
8446 pub const ENCODED_LEN: usize = 28usize;
8447 pub const DEFAULT: Self = Self {
8448 target_system: 0_u8,
8449 control_request: 0_u8,
8450 version: 0_u8,
8451 passkey: [0_u8; 25usize],
8452 };
8453 #[cfg(feature = "arbitrary")]
8454 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8455 use arbitrary::{Arbitrary, Unstructured};
8456 let mut buf = [0u8; 1024];
8457 rng.fill_bytes(&mut buf);
8458 let mut unstructured = Unstructured::new(&buf);
8459 Self::arbitrary(&mut unstructured).unwrap_or_default()
8460 }
8461}
8462impl Default for CHANGE_OPERATOR_CONTROL_DATA {
8463 fn default() -> Self {
8464 Self::DEFAULT.clone()
8465 }
8466}
8467impl MessageData for CHANGE_OPERATOR_CONTROL_DATA {
8468 type Message = MavMessage;
8469 const ID: u32 = 5u32;
8470 const NAME: &'static str = "CHANGE_OPERATOR_CONTROL";
8471 const EXTRA_CRC: u8 = 217u8;
8472 const ENCODED_LEN: usize = 28usize;
8473 fn deser(
8474 _version: MavlinkVersion,
8475 __input: &[u8],
8476 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8477 let avail_len = __input.len();
8478 let mut payload_buf = [0; Self::ENCODED_LEN];
8479 let mut buf = if avail_len < Self::ENCODED_LEN {
8480 payload_buf[0..avail_len].copy_from_slice(__input);
8481 Bytes::new(&payload_buf)
8482 } else {
8483 Bytes::new(__input)
8484 };
8485 let mut __struct = Self::default();
8486 __struct.target_system = buf.get_u8();
8487 __struct.control_request = buf.get_u8();
8488 __struct.version = buf.get_u8();
8489 for v in &mut __struct.passkey {
8490 let val = buf.get_u8();
8491 *v = val;
8492 }
8493 Ok(__struct)
8494 }
8495 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8496 let mut __tmp = BytesMut::new(bytes);
8497 #[allow(clippy::absurd_extreme_comparisons)]
8498 #[allow(unused_comparisons)]
8499 if __tmp.remaining() < Self::ENCODED_LEN {
8500 panic!(
8501 "buffer is too small (need {} bytes, but got {})",
8502 Self::ENCODED_LEN,
8503 __tmp.remaining(),
8504 )
8505 }
8506 __tmp.put_u8(self.target_system);
8507 __tmp.put_u8(self.control_request);
8508 __tmp.put_u8(self.version);
8509 for val in &self.passkey {
8510 __tmp.put_u8(*val);
8511 }
8512 if matches!(version, MavlinkVersion::V2) {
8513 let len = __tmp.len();
8514 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8515 } else {
8516 __tmp.len()
8517 }
8518 }
8519}
8520#[doc = "id: 6"]
8521#[doc = "Accept / deny control of this MAV."]
8522#[derive(Debug, Clone, PartialEq)]
8523#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8524#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8525pub struct CHANGE_OPERATOR_CONTROL_ACK_DATA {
8526 #[doc = "ID of the GCS this message"]
8527 pub gcs_system_id: u8,
8528 #[doc = "0: request control of this MAV, 1: Release control of this MAV"]
8529 pub control_request: u8,
8530 #[doc = "0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control"]
8531 pub ack: u8,
8532}
8533impl CHANGE_OPERATOR_CONTROL_ACK_DATA {
8534 pub const ENCODED_LEN: usize = 3usize;
8535 pub const DEFAULT: Self = Self {
8536 gcs_system_id: 0_u8,
8537 control_request: 0_u8,
8538 ack: 0_u8,
8539 };
8540 #[cfg(feature = "arbitrary")]
8541 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8542 use arbitrary::{Arbitrary, Unstructured};
8543 let mut buf = [0u8; 1024];
8544 rng.fill_bytes(&mut buf);
8545 let mut unstructured = Unstructured::new(&buf);
8546 Self::arbitrary(&mut unstructured).unwrap_or_default()
8547 }
8548}
8549impl Default for CHANGE_OPERATOR_CONTROL_ACK_DATA {
8550 fn default() -> Self {
8551 Self::DEFAULT.clone()
8552 }
8553}
8554impl MessageData for CHANGE_OPERATOR_CONTROL_ACK_DATA {
8555 type Message = MavMessage;
8556 const ID: u32 = 6u32;
8557 const NAME: &'static str = "CHANGE_OPERATOR_CONTROL_ACK";
8558 const EXTRA_CRC: u8 = 104u8;
8559 const ENCODED_LEN: usize = 3usize;
8560 fn deser(
8561 _version: MavlinkVersion,
8562 __input: &[u8],
8563 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8564 let avail_len = __input.len();
8565 let mut payload_buf = [0; Self::ENCODED_LEN];
8566 let mut buf = if avail_len < Self::ENCODED_LEN {
8567 payload_buf[0..avail_len].copy_from_slice(__input);
8568 Bytes::new(&payload_buf)
8569 } else {
8570 Bytes::new(__input)
8571 };
8572 let mut __struct = Self::default();
8573 __struct.gcs_system_id = buf.get_u8();
8574 __struct.control_request = buf.get_u8();
8575 __struct.ack = buf.get_u8();
8576 Ok(__struct)
8577 }
8578 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8579 let mut __tmp = BytesMut::new(bytes);
8580 #[allow(clippy::absurd_extreme_comparisons)]
8581 #[allow(unused_comparisons)]
8582 if __tmp.remaining() < Self::ENCODED_LEN {
8583 panic!(
8584 "buffer is too small (need {} bytes, but got {})",
8585 Self::ENCODED_LEN,
8586 __tmp.remaining(),
8587 )
8588 }
8589 __tmp.put_u8(self.gcs_system_id);
8590 __tmp.put_u8(self.control_request);
8591 __tmp.put_u8(self.ack);
8592 if matches!(version, MavlinkVersion::V2) {
8593 let len = __tmp.len();
8594 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8595 } else {
8596 __tmp.len()
8597 }
8598 }
8599}
8600#[doc = "id: 247"]
8601#[doc = "Information about a potential collision."]
8602#[derive(Debug, Clone, PartialEq)]
8603#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8604#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8605pub struct COLLISION_DATA {
8606 #[doc = "Unique identifier, domain based on src field"]
8607 pub id: u32,
8608 #[doc = "Estimated time until collision occurs"]
8609 pub time_to_minimum_delta: f32,
8610 #[doc = "Closest vertical distance between vehicle and object"]
8611 pub altitude_minimum_delta: f32,
8612 #[doc = "Closest horizontal distance between vehicle and object"]
8613 pub horizontal_minimum_delta: f32,
8614 #[doc = "Collision data source"]
8615 pub src: MavCollisionSrc,
8616 #[doc = "Action that is being taken to avoid this collision"]
8617 pub action: MavCollisionAction,
8618 #[doc = "How concerned the aircraft is about this collision"]
8619 pub threat_level: MavCollisionThreatLevel,
8620}
8621impl COLLISION_DATA {
8622 pub const ENCODED_LEN: usize = 19usize;
8623 pub const DEFAULT: Self = Self {
8624 id: 0_u32,
8625 time_to_minimum_delta: 0.0_f32,
8626 altitude_minimum_delta: 0.0_f32,
8627 horizontal_minimum_delta: 0.0_f32,
8628 src: MavCollisionSrc::DEFAULT,
8629 action: MavCollisionAction::DEFAULT,
8630 threat_level: MavCollisionThreatLevel::DEFAULT,
8631 };
8632 #[cfg(feature = "arbitrary")]
8633 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8634 use arbitrary::{Arbitrary, Unstructured};
8635 let mut buf = [0u8; 1024];
8636 rng.fill_bytes(&mut buf);
8637 let mut unstructured = Unstructured::new(&buf);
8638 Self::arbitrary(&mut unstructured).unwrap_or_default()
8639 }
8640}
8641impl Default for COLLISION_DATA {
8642 fn default() -> Self {
8643 Self::DEFAULT.clone()
8644 }
8645}
8646impl MessageData for COLLISION_DATA {
8647 type Message = MavMessage;
8648 const ID: u32 = 247u32;
8649 const NAME: &'static str = "COLLISION";
8650 const EXTRA_CRC: u8 = 81u8;
8651 const ENCODED_LEN: usize = 19usize;
8652 fn deser(
8653 _version: MavlinkVersion,
8654 __input: &[u8],
8655 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8656 let avail_len = __input.len();
8657 let mut payload_buf = [0; Self::ENCODED_LEN];
8658 let mut buf = if avail_len < Self::ENCODED_LEN {
8659 payload_buf[0..avail_len].copy_from_slice(__input);
8660 Bytes::new(&payload_buf)
8661 } else {
8662 Bytes::new(__input)
8663 };
8664 let mut __struct = Self::default();
8665 __struct.id = buf.get_u32_le();
8666 __struct.time_to_minimum_delta = buf.get_f32_le();
8667 __struct.altitude_minimum_delta = buf.get_f32_le();
8668 __struct.horizontal_minimum_delta = buf.get_f32_le();
8669 let tmp = buf.get_u8();
8670 __struct.src =
8671 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8672 enum_type: "MavCollisionSrc",
8673 value: tmp as u32,
8674 })?;
8675 let tmp = buf.get_u8();
8676 __struct.action =
8677 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8678 enum_type: "MavCollisionAction",
8679 value: tmp as u32,
8680 })?;
8681 let tmp = buf.get_u8();
8682 __struct.threat_level =
8683 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8684 enum_type: "MavCollisionThreatLevel",
8685 value: tmp as u32,
8686 })?;
8687 Ok(__struct)
8688 }
8689 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8690 let mut __tmp = BytesMut::new(bytes);
8691 #[allow(clippy::absurd_extreme_comparisons)]
8692 #[allow(unused_comparisons)]
8693 if __tmp.remaining() < Self::ENCODED_LEN {
8694 panic!(
8695 "buffer is too small (need {} bytes, but got {})",
8696 Self::ENCODED_LEN,
8697 __tmp.remaining(),
8698 )
8699 }
8700 __tmp.put_u32_le(self.id);
8701 __tmp.put_f32_le(self.time_to_minimum_delta);
8702 __tmp.put_f32_le(self.altitude_minimum_delta);
8703 __tmp.put_f32_le(self.horizontal_minimum_delta);
8704 __tmp.put_u8(self.src as u8);
8705 __tmp.put_u8(self.action as u8);
8706 __tmp.put_u8(self.threat_level as u8);
8707 if matches!(version, MavlinkVersion::V2) {
8708 let len = __tmp.len();
8709 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8710 } else {
8711 __tmp.len()
8712 }
8713 }
8714}
8715#[doc = "id: 77"]
8716#[doc = "Report status of a command. Includes feedback whether the command was executed. The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
8717#[derive(Debug, Clone, PartialEq)]
8718#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8719#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8720pub struct COMMAND_ACK_DATA {
8721 #[doc = "Command ID (of acknowledged command)."]
8722 pub command: MavCmd,
8723 #[doc = "Result of command."]
8724 pub result: MavResult,
8725 #[doc = "The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown."]
8726 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8727 pub progress: u8,
8728 #[doc = "Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate \"unused\" or \"unknown\")."]
8729 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8730 pub result_param2: i32,
8731 #[doc = "System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement."]
8732 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8733 pub target_system: u8,
8734 #[doc = "Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement."]
8735 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8736 pub target_component: u8,
8737}
8738impl COMMAND_ACK_DATA {
8739 pub const ENCODED_LEN: usize = 10usize;
8740 pub const DEFAULT: Self = Self {
8741 command: MavCmd::DEFAULT,
8742 result: MavResult::DEFAULT,
8743 progress: 0_u8,
8744 result_param2: 0_i32,
8745 target_system: 0_u8,
8746 target_component: 0_u8,
8747 };
8748 #[cfg(feature = "arbitrary")]
8749 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8750 use arbitrary::{Arbitrary, Unstructured};
8751 let mut buf = [0u8; 1024];
8752 rng.fill_bytes(&mut buf);
8753 let mut unstructured = Unstructured::new(&buf);
8754 Self::arbitrary(&mut unstructured).unwrap_or_default()
8755 }
8756}
8757impl Default for COMMAND_ACK_DATA {
8758 fn default() -> Self {
8759 Self::DEFAULT.clone()
8760 }
8761}
8762impl MessageData for COMMAND_ACK_DATA {
8763 type Message = MavMessage;
8764 const ID: u32 = 77u32;
8765 const NAME: &'static str = "COMMAND_ACK";
8766 const EXTRA_CRC: u8 = 143u8;
8767 const ENCODED_LEN: usize = 10usize;
8768 fn deser(
8769 _version: MavlinkVersion,
8770 __input: &[u8],
8771 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8772 let avail_len = __input.len();
8773 let mut payload_buf = [0; Self::ENCODED_LEN];
8774 let mut buf = if avail_len < Self::ENCODED_LEN {
8775 payload_buf[0..avail_len].copy_from_slice(__input);
8776 Bytes::new(&payload_buf)
8777 } else {
8778 Bytes::new(__input)
8779 };
8780 let mut __struct = Self::default();
8781 let tmp = buf.get_u16_le();
8782 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
8783 ::mavlink_core::error::ParserError::InvalidEnum {
8784 enum_type: "MavCmd",
8785 value: tmp as u32,
8786 },
8787 )?;
8788 let tmp = buf.get_u8();
8789 __struct.result =
8790 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8791 enum_type: "MavResult",
8792 value: tmp as u32,
8793 })?;
8794 __struct.progress = buf.get_u8();
8795 __struct.result_param2 = buf.get_i32_le();
8796 __struct.target_system = buf.get_u8();
8797 __struct.target_component = buf.get_u8();
8798 Ok(__struct)
8799 }
8800 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8801 let mut __tmp = BytesMut::new(bytes);
8802 #[allow(clippy::absurd_extreme_comparisons)]
8803 #[allow(unused_comparisons)]
8804 if __tmp.remaining() < Self::ENCODED_LEN {
8805 panic!(
8806 "buffer is too small (need {} bytes, but got {})",
8807 Self::ENCODED_LEN,
8808 __tmp.remaining(),
8809 )
8810 }
8811 __tmp.put_u16_le(self.command as u16);
8812 __tmp.put_u8(self.result as u8);
8813 __tmp.put_u8(self.progress);
8814 __tmp.put_i32_le(self.result_param2);
8815 __tmp.put_u8(self.target_system);
8816 __tmp.put_u8(self.target_component);
8817 if matches!(version, MavlinkVersion::V2) {
8818 let len = __tmp.len();
8819 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8820 } else {
8821 __tmp.len()
8822 }
8823 }
8824}
8825#[doc = "id: 80"]
8826#[doc = "Cancel a long running command. The target system should respond with a COMMAND_ACK to the original command with result=MAV_RESULT_CANCELLED if the long running process was cancelled. If it has already completed, the cancel action can be ignored. The cancel action can be retried until some sort of acknowledgement to the original command has been received. The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
8827#[derive(Debug, Clone, PartialEq)]
8828#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8829#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8830pub struct COMMAND_CANCEL_DATA {
8831 #[doc = "Command ID (of command to cancel)."]
8832 pub command: MavCmd,
8833 #[doc = "System executing long running command. Should not be broadcast (0)."]
8834 pub target_system: u8,
8835 #[doc = "Component executing long running command."]
8836 pub target_component: u8,
8837}
8838impl COMMAND_CANCEL_DATA {
8839 pub const ENCODED_LEN: usize = 4usize;
8840 pub const DEFAULT: Self = Self {
8841 command: MavCmd::DEFAULT,
8842 target_system: 0_u8,
8843 target_component: 0_u8,
8844 };
8845 #[cfg(feature = "arbitrary")]
8846 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8847 use arbitrary::{Arbitrary, Unstructured};
8848 let mut buf = [0u8; 1024];
8849 rng.fill_bytes(&mut buf);
8850 let mut unstructured = Unstructured::new(&buf);
8851 Self::arbitrary(&mut unstructured).unwrap_or_default()
8852 }
8853}
8854impl Default for COMMAND_CANCEL_DATA {
8855 fn default() -> Self {
8856 Self::DEFAULT.clone()
8857 }
8858}
8859impl MessageData for COMMAND_CANCEL_DATA {
8860 type Message = MavMessage;
8861 const ID: u32 = 80u32;
8862 const NAME: &'static str = "COMMAND_CANCEL";
8863 const EXTRA_CRC: u8 = 14u8;
8864 const ENCODED_LEN: usize = 4usize;
8865 fn deser(
8866 _version: MavlinkVersion,
8867 __input: &[u8],
8868 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8869 let avail_len = __input.len();
8870 let mut payload_buf = [0; Self::ENCODED_LEN];
8871 let mut buf = if avail_len < Self::ENCODED_LEN {
8872 payload_buf[0..avail_len].copy_from_slice(__input);
8873 Bytes::new(&payload_buf)
8874 } else {
8875 Bytes::new(__input)
8876 };
8877 let mut __struct = Self::default();
8878 let tmp = buf.get_u16_le();
8879 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
8880 ::mavlink_core::error::ParserError::InvalidEnum {
8881 enum_type: "MavCmd",
8882 value: tmp as u32,
8883 },
8884 )?;
8885 __struct.target_system = buf.get_u8();
8886 __struct.target_component = buf.get_u8();
8887 Ok(__struct)
8888 }
8889 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8890 let mut __tmp = BytesMut::new(bytes);
8891 #[allow(clippy::absurd_extreme_comparisons)]
8892 #[allow(unused_comparisons)]
8893 if __tmp.remaining() < Self::ENCODED_LEN {
8894 panic!(
8895 "buffer is too small (need {} bytes, but got {})",
8896 Self::ENCODED_LEN,
8897 __tmp.remaining(),
8898 )
8899 }
8900 __tmp.put_u16_le(self.command as u16);
8901 __tmp.put_u8(self.target_system);
8902 __tmp.put_u8(self.target_component);
8903 if matches!(version, MavlinkVersion::V2) {
8904 let len = __tmp.len();
8905 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8906 } else {
8907 __tmp.len()
8908 }
8909 }
8910}
8911#[doc = "id: 75"]
8912#[doc = "Send a command with up to seven parameters to the MAV, where params 5 and 6 are integers and the other values are floats. This is preferred over COMMAND_LONG as it allows the MAV_FRAME to be specified for interpreting positional information, such as altitude. COMMAND_INT is also preferred when sending latitude and longitude data in params 5 and 6, as it allows for greater precision. Param 5 and 6 encode positional data as scaled integers, where the scaling depends on the actual command value. NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
8913#[derive(Debug, Clone, PartialEq)]
8914#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8915#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8916pub struct COMMAND_INT_DATA {
8917 #[doc = "PARAM1, see MAV_CMD enum"]
8918 pub param1: f32,
8919 #[doc = "PARAM2, see MAV_CMD enum"]
8920 pub param2: f32,
8921 #[doc = "PARAM3, see MAV_CMD enum"]
8922 pub param3: f32,
8923 #[doc = "PARAM4, see MAV_CMD enum"]
8924 pub param4: f32,
8925 #[doc = "PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7"]
8926 pub x: i32,
8927 #[doc = "PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7"]
8928 pub y: i32,
8929 #[doc = "PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame)."]
8930 pub z: f32,
8931 #[doc = "The scheduled action for the mission item."]
8932 pub command: MavCmd,
8933 #[doc = "System ID"]
8934 pub target_system: u8,
8935 #[doc = "Component ID"]
8936 pub target_component: u8,
8937 #[doc = "The coordinate system of the COMMAND."]
8938 pub frame: MavFrame,
8939 #[doc = "Not used."]
8940 pub current: u8,
8941 #[doc = "Not used (set 0)."]
8942 pub autocontinue: u8,
8943}
8944impl COMMAND_INT_DATA {
8945 pub const ENCODED_LEN: usize = 35usize;
8946 pub const DEFAULT: Self = Self {
8947 param1: 0.0_f32,
8948 param2: 0.0_f32,
8949 param3: 0.0_f32,
8950 param4: 0.0_f32,
8951 x: 0_i32,
8952 y: 0_i32,
8953 z: 0.0_f32,
8954 command: MavCmd::DEFAULT,
8955 target_system: 0_u8,
8956 target_component: 0_u8,
8957 frame: MavFrame::DEFAULT,
8958 current: 0_u8,
8959 autocontinue: 0_u8,
8960 };
8961 #[cfg(feature = "arbitrary")]
8962 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8963 use arbitrary::{Arbitrary, Unstructured};
8964 let mut buf = [0u8; 1024];
8965 rng.fill_bytes(&mut buf);
8966 let mut unstructured = Unstructured::new(&buf);
8967 Self::arbitrary(&mut unstructured).unwrap_or_default()
8968 }
8969}
8970impl Default for COMMAND_INT_DATA {
8971 fn default() -> Self {
8972 Self::DEFAULT.clone()
8973 }
8974}
8975impl MessageData for COMMAND_INT_DATA {
8976 type Message = MavMessage;
8977 const ID: u32 = 75u32;
8978 const NAME: &'static str = "COMMAND_INT";
8979 const EXTRA_CRC: u8 = 158u8;
8980 const ENCODED_LEN: usize = 35usize;
8981 fn deser(
8982 _version: MavlinkVersion,
8983 __input: &[u8],
8984 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8985 let avail_len = __input.len();
8986 let mut payload_buf = [0; Self::ENCODED_LEN];
8987 let mut buf = if avail_len < Self::ENCODED_LEN {
8988 payload_buf[0..avail_len].copy_from_slice(__input);
8989 Bytes::new(&payload_buf)
8990 } else {
8991 Bytes::new(__input)
8992 };
8993 let mut __struct = Self::default();
8994 __struct.param1 = buf.get_f32_le();
8995 __struct.param2 = buf.get_f32_le();
8996 __struct.param3 = buf.get_f32_le();
8997 __struct.param4 = buf.get_f32_le();
8998 __struct.x = buf.get_i32_le();
8999 __struct.y = buf.get_i32_le();
9000 __struct.z = buf.get_f32_le();
9001 let tmp = buf.get_u16_le();
9002 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
9003 ::mavlink_core::error::ParserError::InvalidEnum {
9004 enum_type: "MavCmd",
9005 value: tmp as u32,
9006 },
9007 )?;
9008 __struct.target_system = buf.get_u8();
9009 __struct.target_component = buf.get_u8();
9010 let tmp = buf.get_u8();
9011 __struct.frame =
9012 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9013 enum_type: "MavFrame",
9014 value: tmp as u32,
9015 })?;
9016 __struct.current = buf.get_u8();
9017 __struct.autocontinue = buf.get_u8();
9018 Ok(__struct)
9019 }
9020 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9021 let mut __tmp = BytesMut::new(bytes);
9022 #[allow(clippy::absurd_extreme_comparisons)]
9023 #[allow(unused_comparisons)]
9024 if __tmp.remaining() < Self::ENCODED_LEN {
9025 panic!(
9026 "buffer is too small (need {} bytes, but got {})",
9027 Self::ENCODED_LEN,
9028 __tmp.remaining(),
9029 )
9030 }
9031 __tmp.put_f32_le(self.param1);
9032 __tmp.put_f32_le(self.param2);
9033 __tmp.put_f32_le(self.param3);
9034 __tmp.put_f32_le(self.param4);
9035 __tmp.put_i32_le(self.x);
9036 __tmp.put_i32_le(self.y);
9037 __tmp.put_f32_le(self.z);
9038 __tmp.put_u16_le(self.command as u16);
9039 __tmp.put_u8(self.target_system);
9040 __tmp.put_u8(self.target_component);
9041 __tmp.put_u8(self.frame as u8);
9042 __tmp.put_u8(self.current);
9043 __tmp.put_u8(self.autocontinue);
9044 if matches!(version, MavlinkVersion::V2) {
9045 let len = __tmp.len();
9046 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9047 } else {
9048 __tmp.len()
9049 }
9050 }
9051}
9052#[doc = "id: 76"]
9053#[doc = "Send a command with up to seven parameters to the MAV. COMMAND_INT is generally preferred when sending MAV_CMD commands that include positional information; it offers higher precision and allows the MAV_FRAME to be specified (which may otherwise be ambiguous, particularly for altitude). The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
9054#[derive(Debug, Clone, PartialEq)]
9055#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9056#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9057pub struct COMMAND_LONG_DATA {
9058 #[doc = "Parameter 1 (for the specific command)."]
9059 pub param1: f32,
9060 #[doc = "Parameter 2 (for the specific command)."]
9061 pub param2: f32,
9062 #[doc = "Parameter 3 (for the specific command)."]
9063 pub param3: f32,
9064 #[doc = "Parameter 4 (for the specific command)."]
9065 pub param4: f32,
9066 #[doc = "Parameter 5 (for the specific command)."]
9067 pub param5: f32,
9068 #[doc = "Parameter 6 (for the specific command)."]
9069 pub param6: f32,
9070 #[doc = "Parameter 7 (for the specific command)."]
9071 pub param7: f32,
9072 #[doc = "Command ID (of command to send)."]
9073 pub command: MavCmd,
9074 #[doc = "System which should execute the command"]
9075 pub target_system: u8,
9076 #[doc = "Component which should execute the command, 0 for all components"]
9077 pub target_component: u8,
9078 #[doc = "0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)"]
9079 pub confirmation: u8,
9080}
9081impl COMMAND_LONG_DATA {
9082 pub const ENCODED_LEN: usize = 33usize;
9083 pub const DEFAULT: Self = Self {
9084 param1: 0.0_f32,
9085 param2: 0.0_f32,
9086 param3: 0.0_f32,
9087 param4: 0.0_f32,
9088 param5: 0.0_f32,
9089 param6: 0.0_f32,
9090 param7: 0.0_f32,
9091 command: MavCmd::DEFAULT,
9092 target_system: 0_u8,
9093 target_component: 0_u8,
9094 confirmation: 0_u8,
9095 };
9096 #[cfg(feature = "arbitrary")]
9097 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9098 use arbitrary::{Arbitrary, Unstructured};
9099 let mut buf = [0u8; 1024];
9100 rng.fill_bytes(&mut buf);
9101 let mut unstructured = Unstructured::new(&buf);
9102 Self::arbitrary(&mut unstructured).unwrap_or_default()
9103 }
9104}
9105impl Default for COMMAND_LONG_DATA {
9106 fn default() -> Self {
9107 Self::DEFAULT.clone()
9108 }
9109}
9110impl MessageData for COMMAND_LONG_DATA {
9111 type Message = MavMessage;
9112 const ID: u32 = 76u32;
9113 const NAME: &'static str = "COMMAND_LONG";
9114 const EXTRA_CRC: u8 = 152u8;
9115 const ENCODED_LEN: usize = 33usize;
9116 fn deser(
9117 _version: MavlinkVersion,
9118 __input: &[u8],
9119 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9120 let avail_len = __input.len();
9121 let mut payload_buf = [0; Self::ENCODED_LEN];
9122 let mut buf = if avail_len < Self::ENCODED_LEN {
9123 payload_buf[0..avail_len].copy_from_slice(__input);
9124 Bytes::new(&payload_buf)
9125 } else {
9126 Bytes::new(__input)
9127 };
9128 let mut __struct = Self::default();
9129 __struct.param1 = buf.get_f32_le();
9130 __struct.param2 = buf.get_f32_le();
9131 __struct.param3 = buf.get_f32_le();
9132 __struct.param4 = buf.get_f32_le();
9133 __struct.param5 = buf.get_f32_le();
9134 __struct.param6 = buf.get_f32_le();
9135 __struct.param7 = buf.get_f32_le();
9136 let tmp = buf.get_u16_le();
9137 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
9138 ::mavlink_core::error::ParserError::InvalidEnum {
9139 enum_type: "MavCmd",
9140 value: tmp as u32,
9141 },
9142 )?;
9143 __struct.target_system = buf.get_u8();
9144 __struct.target_component = buf.get_u8();
9145 __struct.confirmation = buf.get_u8();
9146 Ok(__struct)
9147 }
9148 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9149 let mut __tmp = BytesMut::new(bytes);
9150 #[allow(clippy::absurd_extreme_comparisons)]
9151 #[allow(unused_comparisons)]
9152 if __tmp.remaining() < Self::ENCODED_LEN {
9153 panic!(
9154 "buffer is too small (need {} bytes, but got {})",
9155 Self::ENCODED_LEN,
9156 __tmp.remaining(),
9157 )
9158 }
9159 __tmp.put_f32_le(self.param1);
9160 __tmp.put_f32_le(self.param2);
9161 __tmp.put_f32_le(self.param3);
9162 __tmp.put_f32_le(self.param4);
9163 __tmp.put_f32_le(self.param5);
9164 __tmp.put_f32_le(self.param6);
9165 __tmp.put_f32_le(self.param7);
9166 __tmp.put_u16_le(self.command as u16);
9167 __tmp.put_u8(self.target_system);
9168 __tmp.put_u8(self.target_component);
9169 __tmp.put_u8(self.confirmation);
9170 if matches!(version, MavlinkVersion::V2) {
9171 let len = __tmp.len();
9172 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9173 } else {
9174 __tmp.len()
9175 }
9176 }
9177}
9178#[doc = "id: 395"]
9179#[doc = "Component information message, which may be requested using MAV_CMD_REQUEST_MESSAGE."]
9180#[derive(Debug, Clone, PartialEq)]
9181#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9182#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9183pub struct COMPONENT_INFORMATION_DATA {
9184 #[doc = "Timestamp (time since system boot)."]
9185 pub time_boot_ms: u32,
9186 #[doc = "CRC32 of the general metadata file (general_metadata_uri)."]
9187 pub general_metadata_file_crc: u32,
9188 #[doc = "CRC32 of peripherals metadata file (peripherals_metadata_uri)."]
9189 pub peripherals_metadata_file_crc: u32,
9190 #[doc = "MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated."]
9191 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9192 pub general_metadata_uri: [u8; 100],
9193 #[doc = "(Optional) MAVLink FTP URI for the peripherals metadata file (COMP_METADATA_TYPE_PERIPHERALS), which may be compressed with xz. This contains data about \"attached components\" such as UAVCAN nodes. The peripherals are in a separate file because the information must be generated dynamically at runtime. The string needs to be zero terminated."]
9194 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9195 pub peripherals_metadata_uri: [u8; 100],
9196}
9197impl COMPONENT_INFORMATION_DATA {
9198 pub const ENCODED_LEN: usize = 212usize;
9199 pub const DEFAULT: Self = Self {
9200 time_boot_ms: 0_u32,
9201 general_metadata_file_crc: 0_u32,
9202 peripherals_metadata_file_crc: 0_u32,
9203 general_metadata_uri: [0_u8; 100usize],
9204 peripherals_metadata_uri: [0_u8; 100usize],
9205 };
9206 #[cfg(feature = "arbitrary")]
9207 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9208 use arbitrary::{Arbitrary, Unstructured};
9209 let mut buf = [0u8; 1024];
9210 rng.fill_bytes(&mut buf);
9211 let mut unstructured = Unstructured::new(&buf);
9212 Self::arbitrary(&mut unstructured).unwrap_or_default()
9213 }
9214}
9215impl Default for COMPONENT_INFORMATION_DATA {
9216 fn default() -> Self {
9217 Self::DEFAULT.clone()
9218 }
9219}
9220impl MessageData for COMPONENT_INFORMATION_DATA {
9221 type Message = MavMessage;
9222 const ID: u32 = 395u32;
9223 const NAME: &'static str = "COMPONENT_INFORMATION";
9224 const EXTRA_CRC: u8 = 0u8;
9225 const ENCODED_LEN: usize = 212usize;
9226 fn deser(
9227 _version: MavlinkVersion,
9228 __input: &[u8],
9229 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9230 let avail_len = __input.len();
9231 let mut payload_buf = [0; Self::ENCODED_LEN];
9232 let mut buf = if avail_len < Self::ENCODED_LEN {
9233 payload_buf[0..avail_len].copy_from_slice(__input);
9234 Bytes::new(&payload_buf)
9235 } else {
9236 Bytes::new(__input)
9237 };
9238 let mut __struct = Self::default();
9239 __struct.time_boot_ms = buf.get_u32_le();
9240 __struct.general_metadata_file_crc = buf.get_u32_le();
9241 __struct.peripherals_metadata_file_crc = buf.get_u32_le();
9242 for v in &mut __struct.general_metadata_uri {
9243 let val = buf.get_u8();
9244 *v = val;
9245 }
9246 for v in &mut __struct.peripherals_metadata_uri {
9247 let val = buf.get_u8();
9248 *v = val;
9249 }
9250 Ok(__struct)
9251 }
9252 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9253 let mut __tmp = BytesMut::new(bytes);
9254 #[allow(clippy::absurd_extreme_comparisons)]
9255 #[allow(unused_comparisons)]
9256 if __tmp.remaining() < Self::ENCODED_LEN {
9257 panic!(
9258 "buffer is too small (need {} bytes, but got {})",
9259 Self::ENCODED_LEN,
9260 __tmp.remaining(),
9261 )
9262 }
9263 __tmp.put_u32_le(self.time_boot_ms);
9264 __tmp.put_u32_le(self.general_metadata_file_crc);
9265 __tmp.put_u32_le(self.peripherals_metadata_file_crc);
9266 for val in &self.general_metadata_uri {
9267 __tmp.put_u8(*val);
9268 }
9269 for val in &self.peripherals_metadata_uri {
9270 __tmp.put_u8(*val);
9271 }
9272 if matches!(version, MavlinkVersion::V2) {
9273 let len = __tmp.len();
9274 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9275 } else {
9276 __tmp.len()
9277 }
9278 }
9279}
9280#[doc = "id: 396"]
9281#[doc = "Basic component information data. Should be requested using MAV_CMD_REQUEST_MESSAGE on startup, or when required."]
9282#[derive(Debug, Clone, PartialEq)]
9283#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9284#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9285pub struct COMPONENT_INFORMATION_BASIC_DATA {
9286 #[doc = "Component capability flags"]
9287 pub capabilities: MavProtocolCapability,
9288 #[doc = "Timestamp (time since system boot)."]
9289 pub time_boot_ms: u32,
9290 #[doc = "Date of manufacture as a UNIX Epoch time (since 1.1.1970) in seconds."]
9291 pub time_manufacture_s: u32,
9292 #[doc = "Name of the component vendor. Needs to be zero terminated. The field is optional and can be empty/all zeros."]
9293 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9294 pub vendor_name: [u8; 32],
9295 #[doc = "Name of the component model. Needs to be zero terminated. The field is optional and can be empty/all zeros."]
9296 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9297 pub model_name: [u8; 32],
9298 #[doc = "Software version. The recommended format is SEMVER: 'major.minor.patch' (any format may be used). The field must be zero terminated if it has a value. The field is optional and can be empty/all zeros."]
9299 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9300 pub software_version: [u8; 24],
9301 #[doc = "Hardware version. The recommended format is SEMVER: 'major.minor.patch' (any format may be used). The field must be zero terminated if it has a value. The field is optional and can be empty/all zeros."]
9302 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9303 pub hardware_version: [u8; 24],
9304 #[doc = "Hardware serial number. The field must be zero terminated if it has a value. The field is optional and can be empty/all zeros."]
9305 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9306 pub serial_number: [u8; 32],
9307}
9308impl COMPONENT_INFORMATION_BASIC_DATA {
9309 pub const ENCODED_LEN: usize = 160usize;
9310 pub const DEFAULT: Self = Self {
9311 capabilities: MavProtocolCapability::DEFAULT,
9312 time_boot_ms: 0_u32,
9313 time_manufacture_s: 0_u32,
9314 vendor_name: [0_u8; 32usize],
9315 model_name: [0_u8; 32usize],
9316 software_version: [0_u8; 24usize],
9317 hardware_version: [0_u8; 24usize],
9318 serial_number: [0_u8; 32usize],
9319 };
9320 #[cfg(feature = "arbitrary")]
9321 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9322 use arbitrary::{Arbitrary, Unstructured};
9323 let mut buf = [0u8; 1024];
9324 rng.fill_bytes(&mut buf);
9325 let mut unstructured = Unstructured::new(&buf);
9326 Self::arbitrary(&mut unstructured).unwrap_or_default()
9327 }
9328}
9329impl Default for COMPONENT_INFORMATION_BASIC_DATA {
9330 fn default() -> Self {
9331 Self::DEFAULT.clone()
9332 }
9333}
9334impl MessageData for COMPONENT_INFORMATION_BASIC_DATA {
9335 type Message = MavMessage;
9336 const ID: u32 = 396u32;
9337 const NAME: &'static str = "COMPONENT_INFORMATION_BASIC";
9338 const EXTRA_CRC: u8 = 50u8;
9339 const ENCODED_LEN: usize = 160usize;
9340 fn deser(
9341 _version: MavlinkVersion,
9342 __input: &[u8],
9343 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9344 let avail_len = __input.len();
9345 let mut payload_buf = [0; Self::ENCODED_LEN];
9346 let mut buf = if avail_len < Self::ENCODED_LEN {
9347 payload_buf[0..avail_len].copy_from_slice(__input);
9348 Bytes::new(&payload_buf)
9349 } else {
9350 Bytes::new(__input)
9351 };
9352 let mut __struct = Self::default();
9353 let tmp = buf.get_u64_le();
9354 __struct.capabilities = MavProtocolCapability::from_bits(
9355 tmp & MavProtocolCapability::all().bits(),
9356 )
9357 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
9358 flag_type: "MavProtocolCapability",
9359 value: tmp as u32,
9360 })?;
9361 __struct.time_boot_ms = buf.get_u32_le();
9362 __struct.time_manufacture_s = buf.get_u32_le();
9363 for v in &mut __struct.vendor_name {
9364 let val = buf.get_u8();
9365 *v = val;
9366 }
9367 for v in &mut __struct.model_name {
9368 let val = buf.get_u8();
9369 *v = val;
9370 }
9371 for v in &mut __struct.software_version {
9372 let val = buf.get_u8();
9373 *v = val;
9374 }
9375 for v in &mut __struct.hardware_version {
9376 let val = buf.get_u8();
9377 *v = val;
9378 }
9379 for v in &mut __struct.serial_number {
9380 let val = buf.get_u8();
9381 *v = val;
9382 }
9383 Ok(__struct)
9384 }
9385 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9386 let mut __tmp = BytesMut::new(bytes);
9387 #[allow(clippy::absurd_extreme_comparisons)]
9388 #[allow(unused_comparisons)]
9389 if __tmp.remaining() < Self::ENCODED_LEN {
9390 panic!(
9391 "buffer is too small (need {} bytes, but got {})",
9392 Self::ENCODED_LEN,
9393 __tmp.remaining(),
9394 )
9395 }
9396 __tmp.put_u64_le(self.capabilities.bits());
9397 __tmp.put_u32_le(self.time_boot_ms);
9398 __tmp.put_u32_le(self.time_manufacture_s);
9399 for val in &self.vendor_name {
9400 __tmp.put_u8(*val);
9401 }
9402 for val in &self.model_name {
9403 __tmp.put_u8(*val);
9404 }
9405 for val in &self.software_version {
9406 __tmp.put_u8(*val);
9407 }
9408 for val in &self.hardware_version {
9409 __tmp.put_u8(*val);
9410 }
9411 for val in &self.serial_number {
9412 __tmp.put_u8(*val);
9413 }
9414 if matches!(version, MavlinkVersion::V2) {
9415 let len = __tmp.len();
9416 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9417 } else {
9418 __tmp.len()
9419 }
9420 }
9421}
9422#[doc = "id: 397"]
9423#[doc = "Component metadata message, which may be requested using MAV_CMD_REQUEST_MESSAGE. This contains the MAVLink FTP URI and CRC for the component's general metadata file. The file must be hosted on the component, and may be xz compressed. The file CRC can be used for file caching. The general metadata file can be read to get the locations of other metadata files (COMP_METADATA_TYPE) and translations, which may be hosted either on the vehicle or the internet. For more information see: <https://mavlink.io/en/services/component_information.html>. Note: Camera components should use CAMERA_INFORMATION instead, and autopilots may use both this message and AUTOPILOT_VERSION."]
9424#[derive(Debug, Clone, PartialEq)]
9425#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9426#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9427pub struct COMPONENT_METADATA_DATA {
9428 #[doc = "Timestamp (time since system boot)."]
9429 pub time_boot_ms: u32,
9430 #[doc = "CRC32 of the general metadata file."]
9431 pub file_crc: u32,
9432 #[doc = "MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated."]
9433 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9434 pub uri: [u8; 100],
9435}
9436impl COMPONENT_METADATA_DATA {
9437 pub const ENCODED_LEN: usize = 108usize;
9438 pub const DEFAULT: Self = Self {
9439 time_boot_ms: 0_u32,
9440 file_crc: 0_u32,
9441 uri: [0_u8; 100usize],
9442 };
9443 #[cfg(feature = "arbitrary")]
9444 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9445 use arbitrary::{Arbitrary, Unstructured};
9446 let mut buf = [0u8; 1024];
9447 rng.fill_bytes(&mut buf);
9448 let mut unstructured = Unstructured::new(&buf);
9449 Self::arbitrary(&mut unstructured).unwrap_or_default()
9450 }
9451}
9452impl Default for COMPONENT_METADATA_DATA {
9453 fn default() -> Self {
9454 Self::DEFAULT.clone()
9455 }
9456}
9457impl MessageData for COMPONENT_METADATA_DATA {
9458 type Message = MavMessage;
9459 const ID: u32 = 397u32;
9460 const NAME: &'static str = "COMPONENT_METADATA";
9461 const EXTRA_CRC: u8 = 182u8;
9462 const ENCODED_LEN: usize = 108usize;
9463 fn deser(
9464 _version: MavlinkVersion,
9465 __input: &[u8],
9466 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9467 let avail_len = __input.len();
9468 let mut payload_buf = [0; Self::ENCODED_LEN];
9469 let mut buf = if avail_len < Self::ENCODED_LEN {
9470 payload_buf[0..avail_len].copy_from_slice(__input);
9471 Bytes::new(&payload_buf)
9472 } else {
9473 Bytes::new(__input)
9474 };
9475 let mut __struct = Self::default();
9476 __struct.time_boot_ms = buf.get_u32_le();
9477 __struct.file_crc = buf.get_u32_le();
9478 for v in &mut __struct.uri {
9479 let val = buf.get_u8();
9480 *v = val;
9481 }
9482 Ok(__struct)
9483 }
9484 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9485 let mut __tmp = BytesMut::new(bytes);
9486 #[allow(clippy::absurd_extreme_comparisons)]
9487 #[allow(unused_comparisons)]
9488 if __tmp.remaining() < Self::ENCODED_LEN {
9489 panic!(
9490 "buffer is too small (need {} bytes, but got {})",
9491 Self::ENCODED_LEN,
9492 __tmp.remaining(),
9493 )
9494 }
9495 __tmp.put_u32_le(self.time_boot_ms);
9496 __tmp.put_u32_le(self.file_crc);
9497 for val in &self.uri {
9498 __tmp.put_u8(*val);
9499 }
9500 if matches!(version, MavlinkVersion::V2) {
9501 let len = __tmp.len();
9502 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9503 } else {
9504 __tmp.len()
9505 }
9506 }
9507}
9508#[doc = "id: 146"]
9509#[doc = "The smoothed, monotonic system state used to feed the control loops of the system."]
9510#[derive(Debug, Clone, PartialEq)]
9511#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9512#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9513pub struct CONTROL_SYSTEM_STATE_DATA {
9514 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
9515 pub time_usec: u64,
9516 #[doc = "X acceleration in body frame"]
9517 pub x_acc: f32,
9518 #[doc = "Y acceleration in body frame"]
9519 pub y_acc: f32,
9520 #[doc = "Z acceleration in body frame"]
9521 pub z_acc: f32,
9522 #[doc = "X velocity in body frame"]
9523 pub x_vel: f32,
9524 #[doc = "Y velocity in body frame"]
9525 pub y_vel: f32,
9526 #[doc = "Z velocity in body frame"]
9527 pub z_vel: f32,
9528 #[doc = "X position in local frame"]
9529 pub x_pos: f32,
9530 #[doc = "Y position in local frame"]
9531 pub y_pos: f32,
9532 #[doc = "Z position in local frame"]
9533 pub z_pos: f32,
9534 #[doc = "Airspeed, set to -1 if unknown"]
9535 pub airspeed: f32,
9536 #[doc = "Variance of body velocity estimate"]
9537 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9538 pub vel_variance: [f32; 3],
9539 #[doc = "Variance in local position"]
9540 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9541 pub pos_variance: [f32; 3],
9542 #[doc = "The attitude, represented as Quaternion"]
9543 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9544 pub q: [f32; 4],
9545 #[doc = "Angular rate in roll axis"]
9546 pub roll_rate: f32,
9547 #[doc = "Angular rate in pitch axis"]
9548 pub pitch_rate: f32,
9549 #[doc = "Angular rate in yaw axis"]
9550 pub yaw_rate: f32,
9551}
9552impl CONTROL_SYSTEM_STATE_DATA {
9553 pub const ENCODED_LEN: usize = 100usize;
9554 pub const DEFAULT: Self = Self {
9555 time_usec: 0_u64,
9556 x_acc: 0.0_f32,
9557 y_acc: 0.0_f32,
9558 z_acc: 0.0_f32,
9559 x_vel: 0.0_f32,
9560 y_vel: 0.0_f32,
9561 z_vel: 0.0_f32,
9562 x_pos: 0.0_f32,
9563 y_pos: 0.0_f32,
9564 z_pos: 0.0_f32,
9565 airspeed: 0.0_f32,
9566 vel_variance: [0.0_f32; 3usize],
9567 pos_variance: [0.0_f32; 3usize],
9568 q: [0.0_f32; 4usize],
9569 roll_rate: 0.0_f32,
9570 pitch_rate: 0.0_f32,
9571 yaw_rate: 0.0_f32,
9572 };
9573 #[cfg(feature = "arbitrary")]
9574 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9575 use arbitrary::{Arbitrary, Unstructured};
9576 let mut buf = [0u8; 1024];
9577 rng.fill_bytes(&mut buf);
9578 let mut unstructured = Unstructured::new(&buf);
9579 Self::arbitrary(&mut unstructured).unwrap_or_default()
9580 }
9581}
9582impl Default for CONTROL_SYSTEM_STATE_DATA {
9583 fn default() -> Self {
9584 Self::DEFAULT.clone()
9585 }
9586}
9587impl MessageData for CONTROL_SYSTEM_STATE_DATA {
9588 type Message = MavMessage;
9589 const ID: u32 = 146u32;
9590 const NAME: &'static str = "CONTROL_SYSTEM_STATE";
9591 const EXTRA_CRC: u8 = 103u8;
9592 const ENCODED_LEN: usize = 100usize;
9593 fn deser(
9594 _version: MavlinkVersion,
9595 __input: &[u8],
9596 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9597 let avail_len = __input.len();
9598 let mut payload_buf = [0; Self::ENCODED_LEN];
9599 let mut buf = if avail_len < Self::ENCODED_LEN {
9600 payload_buf[0..avail_len].copy_from_slice(__input);
9601 Bytes::new(&payload_buf)
9602 } else {
9603 Bytes::new(__input)
9604 };
9605 let mut __struct = Self::default();
9606 __struct.time_usec = buf.get_u64_le();
9607 __struct.x_acc = buf.get_f32_le();
9608 __struct.y_acc = buf.get_f32_le();
9609 __struct.z_acc = buf.get_f32_le();
9610 __struct.x_vel = buf.get_f32_le();
9611 __struct.y_vel = buf.get_f32_le();
9612 __struct.z_vel = buf.get_f32_le();
9613 __struct.x_pos = buf.get_f32_le();
9614 __struct.y_pos = buf.get_f32_le();
9615 __struct.z_pos = buf.get_f32_le();
9616 __struct.airspeed = buf.get_f32_le();
9617 for v in &mut __struct.vel_variance {
9618 let val = buf.get_f32_le();
9619 *v = val;
9620 }
9621 for v in &mut __struct.pos_variance {
9622 let val = buf.get_f32_le();
9623 *v = val;
9624 }
9625 for v in &mut __struct.q {
9626 let val = buf.get_f32_le();
9627 *v = val;
9628 }
9629 __struct.roll_rate = buf.get_f32_le();
9630 __struct.pitch_rate = buf.get_f32_le();
9631 __struct.yaw_rate = buf.get_f32_le();
9632 Ok(__struct)
9633 }
9634 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9635 let mut __tmp = BytesMut::new(bytes);
9636 #[allow(clippy::absurd_extreme_comparisons)]
9637 #[allow(unused_comparisons)]
9638 if __tmp.remaining() < Self::ENCODED_LEN {
9639 panic!(
9640 "buffer is too small (need {} bytes, but got {})",
9641 Self::ENCODED_LEN,
9642 __tmp.remaining(),
9643 )
9644 }
9645 __tmp.put_u64_le(self.time_usec);
9646 __tmp.put_f32_le(self.x_acc);
9647 __tmp.put_f32_le(self.y_acc);
9648 __tmp.put_f32_le(self.z_acc);
9649 __tmp.put_f32_le(self.x_vel);
9650 __tmp.put_f32_le(self.y_vel);
9651 __tmp.put_f32_le(self.z_vel);
9652 __tmp.put_f32_le(self.x_pos);
9653 __tmp.put_f32_le(self.y_pos);
9654 __tmp.put_f32_le(self.z_pos);
9655 __tmp.put_f32_le(self.airspeed);
9656 for val in &self.vel_variance {
9657 __tmp.put_f32_le(*val);
9658 }
9659 for val in &self.pos_variance {
9660 __tmp.put_f32_le(*val);
9661 }
9662 for val in &self.q {
9663 __tmp.put_f32_le(*val);
9664 }
9665 __tmp.put_f32_le(self.roll_rate);
9666 __tmp.put_f32_le(self.pitch_rate);
9667 __tmp.put_f32_le(self.yaw_rate);
9668 if matches!(version, MavlinkVersion::V2) {
9669 let len = __tmp.len();
9670 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9671 } else {
9672 __tmp.len()
9673 }
9674 }
9675}
9676#[doc = "id: 411"]
9677#[doc = "Regular broadcast for the current latest event sequence number for a component. This is used to check for dropped events."]
9678#[derive(Debug, Clone, PartialEq)]
9679#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9680#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9681pub struct CURRENT_EVENT_SEQUENCE_DATA {
9682 #[doc = "Sequence number."]
9683 pub sequence: u16,
9684 #[doc = "Flag bitset."]
9685 pub flags: MavEventCurrentSequenceFlags,
9686}
9687impl CURRENT_EVENT_SEQUENCE_DATA {
9688 pub const ENCODED_LEN: usize = 3usize;
9689 pub const DEFAULT: Self = Self {
9690 sequence: 0_u16,
9691 flags: MavEventCurrentSequenceFlags::DEFAULT,
9692 };
9693 #[cfg(feature = "arbitrary")]
9694 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9695 use arbitrary::{Arbitrary, Unstructured};
9696 let mut buf = [0u8; 1024];
9697 rng.fill_bytes(&mut buf);
9698 let mut unstructured = Unstructured::new(&buf);
9699 Self::arbitrary(&mut unstructured).unwrap_or_default()
9700 }
9701}
9702impl Default for CURRENT_EVENT_SEQUENCE_DATA {
9703 fn default() -> Self {
9704 Self::DEFAULT.clone()
9705 }
9706}
9707impl MessageData for CURRENT_EVENT_SEQUENCE_DATA {
9708 type Message = MavMessage;
9709 const ID: u32 = 411u32;
9710 const NAME: &'static str = "CURRENT_EVENT_SEQUENCE";
9711 const EXTRA_CRC: u8 = 106u8;
9712 const ENCODED_LEN: usize = 3usize;
9713 fn deser(
9714 _version: MavlinkVersion,
9715 __input: &[u8],
9716 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9717 let avail_len = __input.len();
9718 let mut payload_buf = [0; Self::ENCODED_LEN];
9719 let mut buf = if avail_len < Self::ENCODED_LEN {
9720 payload_buf[0..avail_len].copy_from_slice(__input);
9721 Bytes::new(&payload_buf)
9722 } else {
9723 Bytes::new(__input)
9724 };
9725 let mut __struct = Self::default();
9726 __struct.sequence = buf.get_u16_le();
9727 let tmp = buf.get_u8();
9728 __struct.flags =
9729 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9730 enum_type: "MavEventCurrentSequenceFlags",
9731 value: tmp as u32,
9732 })?;
9733 Ok(__struct)
9734 }
9735 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9736 let mut __tmp = BytesMut::new(bytes);
9737 #[allow(clippy::absurd_extreme_comparisons)]
9738 #[allow(unused_comparisons)]
9739 if __tmp.remaining() < Self::ENCODED_LEN {
9740 panic!(
9741 "buffer is too small (need {} bytes, but got {})",
9742 Self::ENCODED_LEN,
9743 __tmp.remaining(),
9744 )
9745 }
9746 __tmp.put_u16_le(self.sequence);
9747 __tmp.put_u8(self.flags as u8);
9748 if matches!(version, MavlinkVersion::V2) {
9749 let len = __tmp.len();
9750 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9751 } else {
9752 __tmp.len()
9753 }
9754 }
9755}
9756#[doc = "id: 436"]
9757#[doc = "Get the current mode. This should be emitted on any mode change, and broadcast at low rate (nominally 0.5 Hz). It may be requested using MAV_CMD_REQUEST_MESSAGE. See <https://mavlink.io/en/services/standard_modes.html>."]
9758#[derive(Debug, Clone, PartialEq)]
9759#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9760#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9761pub struct CURRENT_MODE_DATA {
9762 #[doc = "A bitfield for use for autopilot-specific flags"]
9763 pub custom_mode: u32,
9764 #[doc = "The custom_mode of the mode that was last commanded by the user (for example, with MAV_CMD_DO_SET_STANDARD_MODE, MAV_CMD_DO_SET_MODE or via RC). This should usually be the same as custom_mode. It will be different if the vehicle is unable to enter the intended mode, or has left that mode due to a failsafe condition. 0 indicates the intended custom mode is unknown/not supplied"]
9765 pub intended_custom_mode: u32,
9766 #[doc = "Standard mode."]
9767 pub standard_mode: MavStandardMode,
9768}
9769impl CURRENT_MODE_DATA {
9770 pub const ENCODED_LEN: usize = 9usize;
9771 pub const DEFAULT: Self = Self {
9772 custom_mode: 0_u32,
9773 intended_custom_mode: 0_u32,
9774 standard_mode: MavStandardMode::DEFAULT,
9775 };
9776 #[cfg(feature = "arbitrary")]
9777 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9778 use arbitrary::{Arbitrary, Unstructured};
9779 let mut buf = [0u8; 1024];
9780 rng.fill_bytes(&mut buf);
9781 let mut unstructured = Unstructured::new(&buf);
9782 Self::arbitrary(&mut unstructured).unwrap_or_default()
9783 }
9784}
9785impl Default for CURRENT_MODE_DATA {
9786 fn default() -> Self {
9787 Self::DEFAULT.clone()
9788 }
9789}
9790impl MessageData for CURRENT_MODE_DATA {
9791 type Message = MavMessage;
9792 const ID: u32 = 436u32;
9793 const NAME: &'static str = "CURRENT_MODE";
9794 const EXTRA_CRC: u8 = 193u8;
9795 const ENCODED_LEN: usize = 9usize;
9796 fn deser(
9797 _version: MavlinkVersion,
9798 __input: &[u8],
9799 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9800 let avail_len = __input.len();
9801 let mut payload_buf = [0; Self::ENCODED_LEN];
9802 let mut buf = if avail_len < Self::ENCODED_LEN {
9803 payload_buf[0..avail_len].copy_from_slice(__input);
9804 Bytes::new(&payload_buf)
9805 } else {
9806 Bytes::new(__input)
9807 };
9808 let mut __struct = Self::default();
9809 __struct.custom_mode = buf.get_u32_le();
9810 __struct.intended_custom_mode = buf.get_u32_le();
9811 let tmp = buf.get_u8();
9812 __struct.standard_mode =
9813 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9814 enum_type: "MavStandardMode",
9815 value: tmp as u32,
9816 })?;
9817 Ok(__struct)
9818 }
9819 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9820 let mut __tmp = BytesMut::new(bytes);
9821 #[allow(clippy::absurd_extreme_comparisons)]
9822 #[allow(unused_comparisons)]
9823 if __tmp.remaining() < Self::ENCODED_LEN {
9824 panic!(
9825 "buffer is too small (need {} bytes, but got {})",
9826 Self::ENCODED_LEN,
9827 __tmp.remaining(),
9828 )
9829 }
9830 __tmp.put_u32_le(self.custom_mode);
9831 __tmp.put_u32_le(self.intended_custom_mode);
9832 __tmp.put_u8(self.standard_mode as u8);
9833 if matches!(version, MavlinkVersion::V2) {
9834 let len = __tmp.len();
9835 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9836 } else {
9837 __tmp.len()
9838 }
9839 }
9840}
9841#[doc = "id: 67"]
9842#[doc = "Data stream status information."]
9843#[derive(Debug, Clone, PartialEq)]
9844#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9845#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9846pub struct DATA_STREAM_DATA {
9847 #[doc = "The message rate"]
9848 pub message_rate: u16,
9849 #[doc = "The ID of the requested data stream"]
9850 pub stream_id: u8,
9851 #[doc = "1 stream is enabled, 0 stream is stopped."]
9852 pub on_off: u8,
9853}
9854impl DATA_STREAM_DATA {
9855 pub const ENCODED_LEN: usize = 4usize;
9856 pub const DEFAULT: Self = Self {
9857 message_rate: 0_u16,
9858 stream_id: 0_u8,
9859 on_off: 0_u8,
9860 };
9861 #[cfg(feature = "arbitrary")]
9862 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9863 use arbitrary::{Arbitrary, Unstructured};
9864 let mut buf = [0u8; 1024];
9865 rng.fill_bytes(&mut buf);
9866 let mut unstructured = Unstructured::new(&buf);
9867 Self::arbitrary(&mut unstructured).unwrap_or_default()
9868 }
9869}
9870impl Default for DATA_STREAM_DATA {
9871 fn default() -> Self {
9872 Self::DEFAULT.clone()
9873 }
9874}
9875impl MessageData for DATA_STREAM_DATA {
9876 type Message = MavMessage;
9877 const ID: u32 = 67u32;
9878 const NAME: &'static str = "DATA_STREAM";
9879 const EXTRA_CRC: u8 = 21u8;
9880 const ENCODED_LEN: usize = 4usize;
9881 fn deser(
9882 _version: MavlinkVersion,
9883 __input: &[u8],
9884 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9885 let avail_len = __input.len();
9886 let mut payload_buf = [0; Self::ENCODED_LEN];
9887 let mut buf = if avail_len < Self::ENCODED_LEN {
9888 payload_buf[0..avail_len].copy_from_slice(__input);
9889 Bytes::new(&payload_buf)
9890 } else {
9891 Bytes::new(__input)
9892 };
9893 let mut __struct = Self::default();
9894 __struct.message_rate = buf.get_u16_le();
9895 __struct.stream_id = buf.get_u8();
9896 __struct.on_off = buf.get_u8();
9897 Ok(__struct)
9898 }
9899 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9900 let mut __tmp = BytesMut::new(bytes);
9901 #[allow(clippy::absurd_extreme_comparisons)]
9902 #[allow(unused_comparisons)]
9903 if __tmp.remaining() < Self::ENCODED_LEN {
9904 panic!(
9905 "buffer is too small (need {} bytes, but got {})",
9906 Self::ENCODED_LEN,
9907 __tmp.remaining(),
9908 )
9909 }
9910 __tmp.put_u16_le(self.message_rate);
9911 __tmp.put_u8(self.stream_id);
9912 __tmp.put_u8(self.on_off);
9913 if matches!(version, MavlinkVersion::V2) {
9914 let len = __tmp.len();
9915 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9916 } else {
9917 __tmp.len()
9918 }
9919 }
9920}
9921#[doc = "id: 130"]
9922#[doc = "Handshake message to initiate, control and stop image streaming when using the Image Transmission Protocol: <https://mavlink.io/en/services/image_transmission.html>."]
9923#[derive(Debug, Clone, PartialEq)]
9924#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9925#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9926pub struct DATA_TRANSMISSION_HANDSHAKE_DATA {
9927 #[doc = "total data size (set on ACK only)."]
9928 pub size: u32,
9929 #[doc = "Width of a matrix or image."]
9930 pub width: u16,
9931 #[doc = "Height of a matrix or image."]
9932 pub height: u16,
9933 #[doc = "Number of packets being sent (set on ACK only)."]
9934 pub packets: u16,
9935 #[doc = "Type of requested/acknowledged data."]
9936 pub mavtype: MavlinkDataStreamType,
9937 #[doc = "Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)."]
9938 pub payload: u8,
9939 #[doc = "JPEG quality. Values: [1-100]."]
9940 pub jpg_quality: u8,
9941}
9942impl DATA_TRANSMISSION_HANDSHAKE_DATA {
9943 pub const ENCODED_LEN: usize = 13usize;
9944 pub const DEFAULT: Self = Self {
9945 size: 0_u32,
9946 width: 0_u16,
9947 height: 0_u16,
9948 packets: 0_u16,
9949 mavtype: MavlinkDataStreamType::DEFAULT,
9950 payload: 0_u8,
9951 jpg_quality: 0_u8,
9952 };
9953 #[cfg(feature = "arbitrary")]
9954 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9955 use arbitrary::{Arbitrary, Unstructured};
9956 let mut buf = [0u8; 1024];
9957 rng.fill_bytes(&mut buf);
9958 let mut unstructured = Unstructured::new(&buf);
9959 Self::arbitrary(&mut unstructured).unwrap_or_default()
9960 }
9961}
9962impl Default for DATA_TRANSMISSION_HANDSHAKE_DATA {
9963 fn default() -> Self {
9964 Self::DEFAULT.clone()
9965 }
9966}
9967impl MessageData for DATA_TRANSMISSION_HANDSHAKE_DATA {
9968 type Message = MavMessage;
9969 const ID: u32 = 130u32;
9970 const NAME: &'static str = "DATA_TRANSMISSION_HANDSHAKE";
9971 const EXTRA_CRC: u8 = 29u8;
9972 const ENCODED_LEN: usize = 13usize;
9973 fn deser(
9974 _version: MavlinkVersion,
9975 __input: &[u8],
9976 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9977 let avail_len = __input.len();
9978 let mut payload_buf = [0; Self::ENCODED_LEN];
9979 let mut buf = if avail_len < Self::ENCODED_LEN {
9980 payload_buf[0..avail_len].copy_from_slice(__input);
9981 Bytes::new(&payload_buf)
9982 } else {
9983 Bytes::new(__input)
9984 };
9985 let mut __struct = Self::default();
9986 __struct.size = buf.get_u32_le();
9987 __struct.width = buf.get_u16_le();
9988 __struct.height = buf.get_u16_le();
9989 __struct.packets = buf.get_u16_le();
9990 let tmp = buf.get_u8();
9991 __struct.mavtype =
9992 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9993 enum_type: "MavlinkDataStreamType",
9994 value: tmp as u32,
9995 })?;
9996 __struct.payload = buf.get_u8();
9997 __struct.jpg_quality = buf.get_u8();
9998 Ok(__struct)
9999 }
10000 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10001 let mut __tmp = BytesMut::new(bytes);
10002 #[allow(clippy::absurd_extreme_comparisons)]
10003 #[allow(unused_comparisons)]
10004 if __tmp.remaining() < Self::ENCODED_LEN {
10005 panic!(
10006 "buffer is too small (need {} bytes, but got {})",
10007 Self::ENCODED_LEN,
10008 __tmp.remaining(),
10009 )
10010 }
10011 __tmp.put_u32_le(self.size);
10012 __tmp.put_u16_le(self.width);
10013 __tmp.put_u16_le(self.height);
10014 __tmp.put_u16_le(self.packets);
10015 __tmp.put_u8(self.mavtype as u8);
10016 __tmp.put_u8(self.payload);
10017 __tmp.put_u8(self.jpg_quality);
10018 if matches!(version, MavlinkVersion::V2) {
10019 let len = __tmp.len();
10020 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10021 } else {
10022 __tmp.len()
10023 }
10024 }
10025}
10026#[doc = "id: 254"]
10027#[doc = "Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N."]
10028#[derive(Debug, Clone, PartialEq)]
10029#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10030#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10031pub struct DEBUG_DATA {
10032 #[doc = "Timestamp (time since system boot)."]
10033 pub time_boot_ms: u32,
10034 #[doc = "DEBUG value"]
10035 pub value: f32,
10036 #[doc = "index of debug variable"]
10037 pub ind: u8,
10038}
10039impl DEBUG_DATA {
10040 pub const ENCODED_LEN: usize = 9usize;
10041 pub const DEFAULT: Self = Self {
10042 time_boot_ms: 0_u32,
10043 value: 0.0_f32,
10044 ind: 0_u8,
10045 };
10046 #[cfg(feature = "arbitrary")]
10047 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10048 use arbitrary::{Arbitrary, Unstructured};
10049 let mut buf = [0u8; 1024];
10050 rng.fill_bytes(&mut buf);
10051 let mut unstructured = Unstructured::new(&buf);
10052 Self::arbitrary(&mut unstructured).unwrap_or_default()
10053 }
10054}
10055impl Default for DEBUG_DATA {
10056 fn default() -> Self {
10057 Self::DEFAULT.clone()
10058 }
10059}
10060impl MessageData for DEBUG_DATA {
10061 type Message = MavMessage;
10062 const ID: u32 = 254u32;
10063 const NAME: &'static str = "DEBUG";
10064 const EXTRA_CRC: u8 = 46u8;
10065 const ENCODED_LEN: usize = 9usize;
10066 fn deser(
10067 _version: MavlinkVersion,
10068 __input: &[u8],
10069 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10070 let avail_len = __input.len();
10071 let mut payload_buf = [0; Self::ENCODED_LEN];
10072 let mut buf = if avail_len < Self::ENCODED_LEN {
10073 payload_buf[0..avail_len].copy_from_slice(__input);
10074 Bytes::new(&payload_buf)
10075 } else {
10076 Bytes::new(__input)
10077 };
10078 let mut __struct = Self::default();
10079 __struct.time_boot_ms = buf.get_u32_le();
10080 __struct.value = buf.get_f32_le();
10081 __struct.ind = buf.get_u8();
10082 Ok(__struct)
10083 }
10084 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10085 let mut __tmp = BytesMut::new(bytes);
10086 #[allow(clippy::absurd_extreme_comparisons)]
10087 #[allow(unused_comparisons)]
10088 if __tmp.remaining() < Self::ENCODED_LEN {
10089 panic!(
10090 "buffer is too small (need {} bytes, but got {})",
10091 Self::ENCODED_LEN,
10092 __tmp.remaining(),
10093 )
10094 }
10095 __tmp.put_u32_le(self.time_boot_ms);
10096 __tmp.put_f32_le(self.value);
10097 __tmp.put_u8(self.ind);
10098 if matches!(version, MavlinkVersion::V2) {
10099 let len = __tmp.len();
10100 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10101 } else {
10102 __tmp.len()
10103 }
10104 }
10105}
10106#[doc = "id: 350"]
10107#[doc = "Large debug/prototyping array. The message uses the maximum available payload for data. The array_id and name fields are used to discriminate between messages in code and in user interfaces (respectively). Do not use in production code."]
10108#[derive(Debug, Clone, PartialEq)]
10109#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10110#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10111pub struct DEBUG_FLOAT_ARRAY_DATA {
10112 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
10113 pub time_usec: u64,
10114 #[doc = "Unique ID used to discriminate between arrays"]
10115 pub array_id: u16,
10116 #[doc = "Name, for human-friendly display in a Ground Control Station"]
10117 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10118 pub name: [u8; 10],
10119 #[doc = "data"]
10120 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
10121 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10122 pub data: [f32; 58],
10123}
10124impl DEBUG_FLOAT_ARRAY_DATA {
10125 pub const ENCODED_LEN: usize = 252usize;
10126 pub const DEFAULT: Self = Self {
10127 time_usec: 0_u64,
10128 array_id: 0_u16,
10129 name: [0_u8; 10usize],
10130 data: [0.0_f32; 58usize],
10131 };
10132 #[cfg(feature = "arbitrary")]
10133 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10134 use arbitrary::{Arbitrary, Unstructured};
10135 let mut buf = [0u8; 1024];
10136 rng.fill_bytes(&mut buf);
10137 let mut unstructured = Unstructured::new(&buf);
10138 Self::arbitrary(&mut unstructured).unwrap_or_default()
10139 }
10140}
10141impl Default for DEBUG_FLOAT_ARRAY_DATA {
10142 fn default() -> Self {
10143 Self::DEFAULT.clone()
10144 }
10145}
10146impl MessageData for DEBUG_FLOAT_ARRAY_DATA {
10147 type Message = MavMessage;
10148 const ID: u32 = 350u32;
10149 const NAME: &'static str = "DEBUG_FLOAT_ARRAY";
10150 const EXTRA_CRC: u8 = 232u8;
10151 const ENCODED_LEN: usize = 252usize;
10152 fn deser(
10153 _version: MavlinkVersion,
10154 __input: &[u8],
10155 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10156 let avail_len = __input.len();
10157 let mut payload_buf = [0; Self::ENCODED_LEN];
10158 let mut buf = if avail_len < Self::ENCODED_LEN {
10159 payload_buf[0..avail_len].copy_from_slice(__input);
10160 Bytes::new(&payload_buf)
10161 } else {
10162 Bytes::new(__input)
10163 };
10164 let mut __struct = Self::default();
10165 __struct.time_usec = buf.get_u64_le();
10166 __struct.array_id = buf.get_u16_le();
10167 for v in &mut __struct.name {
10168 let val = buf.get_u8();
10169 *v = val;
10170 }
10171 for v in &mut __struct.data {
10172 let val = buf.get_f32_le();
10173 *v = val;
10174 }
10175 Ok(__struct)
10176 }
10177 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10178 let mut __tmp = BytesMut::new(bytes);
10179 #[allow(clippy::absurd_extreme_comparisons)]
10180 #[allow(unused_comparisons)]
10181 if __tmp.remaining() < Self::ENCODED_LEN {
10182 panic!(
10183 "buffer is too small (need {} bytes, but got {})",
10184 Self::ENCODED_LEN,
10185 __tmp.remaining(),
10186 )
10187 }
10188 __tmp.put_u64_le(self.time_usec);
10189 __tmp.put_u16_le(self.array_id);
10190 for val in &self.name {
10191 __tmp.put_u8(*val);
10192 }
10193 for val in &self.data {
10194 __tmp.put_f32_le(*val);
10195 }
10196 if matches!(version, MavlinkVersion::V2) {
10197 let len = __tmp.len();
10198 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10199 } else {
10200 __tmp.len()
10201 }
10202 }
10203}
10204#[doc = "id: 250"]
10205#[doc = "To debug something using a named 3D vector."]
10206#[derive(Debug, Clone, PartialEq)]
10207#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10208#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10209pub struct DEBUG_VECT_DATA {
10210 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
10211 pub time_usec: u64,
10212 #[doc = "x"]
10213 pub x: f32,
10214 #[doc = "y"]
10215 pub y: f32,
10216 #[doc = "z"]
10217 pub z: f32,
10218 #[doc = "Name"]
10219 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10220 pub name: [u8; 10],
10221}
10222impl DEBUG_VECT_DATA {
10223 pub const ENCODED_LEN: usize = 30usize;
10224 pub const DEFAULT: Self = Self {
10225 time_usec: 0_u64,
10226 x: 0.0_f32,
10227 y: 0.0_f32,
10228 z: 0.0_f32,
10229 name: [0_u8; 10usize],
10230 };
10231 #[cfg(feature = "arbitrary")]
10232 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10233 use arbitrary::{Arbitrary, Unstructured};
10234 let mut buf = [0u8; 1024];
10235 rng.fill_bytes(&mut buf);
10236 let mut unstructured = Unstructured::new(&buf);
10237 Self::arbitrary(&mut unstructured).unwrap_or_default()
10238 }
10239}
10240impl Default for DEBUG_VECT_DATA {
10241 fn default() -> Self {
10242 Self::DEFAULT.clone()
10243 }
10244}
10245impl MessageData for DEBUG_VECT_DATA {
10246 type Message = MavMessage;
10247 const ID: u32 = 250u32;
10248 const NAME: &'static str = "DEBUG_VECT";
10249 const EXTRA_CRC: u8 = 49u8;
10250 const ENCODED_LEN: usize = 30usize;
10251 fn deser(
10252 _version: MavlinkVersion,
10253 __input: &[u8],
10254 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10255 let avail_len = __input.len();
10256 let mut payload_buf = [0; Self::ENCODED_LEN];
10257 let mut buf = if avail_len < Self::ENCODED_LEN {
10258 payload_buf[0..avail_len].copy_from_slice(__input);
10259 Bytes::new(&payload_buf)
10260 } else {
10261 Bytes::new(__input)
10262 };
10263 let mut __struct = Self::default();
10264 __struct.time_usec = buf.get_u64_le();
10265 __struct.x = buf.get_f32_le();
10266 __struct.y = buf.get_f32_le();
10267 __struct.z = buf.get_f32_le();
10268 for v in &mut __struct.name {
10269 let val = buf.get_u8();
10270 *v = val;
10271 }
10272 Ok(__struct)
10273 }
10274 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10275 let mut __tmp = BytesMut::new(bytes);
10276 #[allow(clippy::absurd_extreme_comparisons)]
10277 #[allow(unused_comparisons)]
10278 if __tmp.remaining() < Self::ENCODED_LEN {
10279 panic!(
10280 "buffer is too small (need {} bytes, but got {})",
10281 Self::ENCODED_LEN,
10282 __tmp.remaining(),
10283 )
10284 }
10285 __tmp.put_u64_le(self.time_usec);
10286 __tmp.put_f32_le(self.x);
10287 __tmp.put_f32_le(self.y);
10288 __tmp.put_f32_le(self.z);
10289 for val in &self.name {
10290 __tmp.put_u8(*val);
10291 }
10292 if matches!(version, MavlinkVersion::V2) {
10293 let len = __tmp.len();
10294 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10295 } else {
10296 __tmp.len()
10297 }
10298 }
10299}
10300#[doc = "id: 132"]
10301#[doc = "Distance sensor information for an onboard rangefinder."]
10302#[derive(Debug, Clone, PartialEq)]
10303#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10304#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10305pub struct DISTANCE_SENSOR_DATA {
10306 #[doc = "Timestamp (time since system boot)."]
10307 pub time_boot_ms: u32,
10308 #[doc = "Minimum distance the sensor can measure"]
10309 pub min_distance: u16,
10310 #[doc = "Maximum distance the sensor can measure"]
10311 pub max_distance: u16,
10312 #[doc = "Current distance reading"]
10313 pub current_distance: u16,
10314 #[doc = "Type of distance sensor."]
10315 pub mavtype: MavDistanceSensor,
10316 #[doc = "Onboard ID of the sensor"]
10317 pub id: u8,
10318 #[doc = "Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270"]
10319 pub orientation: MavSensorOrientation,
10320 #[doc = "Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown."]
10321 pub covariance: u8,
10322 #[doc = "Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0."]
10323 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
10324 pub horizontal_fov: f32,
10325 #[doc = "Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0."]
10326 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
10327 pub vertical_fov: f32,
10328 #[doc = "Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid.\""]
10329 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
10330 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10331 pub quaternion: [f32; 4],
10332 #[doc = "Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal."]
10333 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
10334 pub signal_quality: u8,
10335}
10336impl DISTANCE_SENSOR_DATA {
10337 pub const ENCODED_LEN: usize = 39usize;
10338 pub const DEFAULT: Self = Self {
10339 time_boot_ms: 0_u32,
10340 min_distance: 0_u16,
10341 max_distance: 0_u16,
10342 current_distance: 0_u16,
10343 mavtype: MavDistanceSensor::DEFAULT,
10344 id: 0_u8,
10345 orientation: MavSensorOrientation::DEFAULT,
10346 covariance: 0_u8,
10347 horizontal_fov: 0.0_f32,
10348 vertical_fov: 0.0_f32,
10349 quaternion: [0.0_f32; 4usize],
10350 signal_quality: 0_u8,
10351 };
10352 #[cfg(feature = "arbitrary")]
10353 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10354 use arbitrary::{Arbitrary, Unstructured};
10355 let mut buf = [0u8; 1024];
10356 rng.fill_bytes(&mut buf);
10357 let mut unstructured = Unstructured::new(&buf);
10358 Self::arbitrary(&mut unstructured).unwrap_or_default()
10359 }
10360}
10361impl Default for DISTANCE_SENSOR_DATA {
10362 fn default() -> Self {
10363 Self::DEFAULT.clone()
10364 }
10365}
10366impl MessageData for DISTANCE_SENSOR_DATA {
10367 type Message = MavMessage;
10368 const ID: u32 = 132u32;
10369 const NAME: &'static str = "DISTANCE_SENSOR";
10370 const EXTRA_CRC: u8 = 85u8;
10371 const ENCODED_LEN: usize = 39usize;
10372 fn deser(
10373 _version: MavlinkVersion,
10374 __input: &[u8],
10375 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10376 let avail_len = __input.len();
10377 let mut payload_buf = [0; Self::ENCODED_LEN];
10378 let mut buf = if avail_len < Self::ENCODED_LEN {
10379 payload_buf[0..avail_len].copy_from_slice(__input);
10380 Bytes::new(&payload_buf)
10381 } else {
10382 Bytes::new(__input)
10383 };
10384 let mut __struct = Self::default();
10385 __struct.time_boot_ms = buf.get_u32_le();
10386 __struct.min_distance = buf.get_u16_le();
10387 __struct.max_distance = buf.get_u16_le();
10388 __struct.current_distance = buf.get_u16_le();
10389 let tmp = buf.get_u8();
10390 __struct.mavtype =
10391 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10392 enum_type: "MavDistanceSensor",
10393 value: tmp as u32,
10394 })?;
10395 __struct.id = buf.get_u8();
10396 let tmp = buf.get_u8();
10397 __struct.orientation =
10398 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10399 enum_type: "MavSensorOrientation",
10400 value: tmp as u32,
10401 })?;
10402 __struct.covariance = buf.get_u8();
10403 __struct.horizontal_fov = buf.get_f32_le();
10404 __struct.vertical_fov = buf.get_f32_le();
10405 for v in &mut __struct.quaternion {
10406 let val = buf.get_f32_le();
10407 *v = val;
10408 }
10409 __struct.signal_quality = buf.get_u8();
10410 Ok(__struct)
10411 }
10412 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10413 let mut __tmp = BytesMut::new(bytes);
10414 #[allow(clippy::absurd_extreme_comparisons)]
10415 #[allow(unused_comparisons)]
10416 if __tmp.remaining() < Self::ENCODED_LEN {
10417 panic!(
10418 "buffer is too small (need {} bytes, but got {})",
10419 Self::ENCODED_LEN,
10420 __tmp.remaining(),
10421 )
10422 }
10423 __tmp.put_u32_le(self.time_boot_ms);
10424 __tmp.put_u16_le(self.min_distance);
10425 __tmp.put_u16_le(self.max_distance);
10426 __tmp.put_u16_le(self.current_distance);
10427 __tmp.put_u8(self.mavtype as u8);
10428 __tmp.put_u8(self.id);
10429 __tmp.put_u8(self.orientation as u8);
10430 __tmp.put_u8(self.covariance);
10431 __tmp.put_f32_le(self.horizontal_fov);
10432 __tmp.put_f32_le(self.vertical_fov);
10433 for val in &self.quaternion {
10434 __tmp.put_f32_le(*val);
10435 }
10436 __tmp.put_u8(self.signal_quality);
10437 if matches!(version, MavlinkVersion::V2) {
10438 let len = __tmp.len();
10439 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10440 } else {
10441 __tmp.len()
10442 }
10443 }
10444}
10445#[doc = "id: 225"]
10446#[doc = "EFI status output."]
10447#[derive(Debug, Clone, PartialEq)]
10448#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10449#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10450pub struct EFI_STATUS_DATA {
10451 #[doc = "ECU index"]
10452 pub ecu_index: f32,
10453 #[doc = "RPM"]
10454 pub rpm: f32,
10455 #[doc = "Fuel consumed"]
10456 pub fuel_consumed: f32,
10457 #[doc = "Fuel flow rate"]
10458 pub fuel_flow: f32,
10459 #[doc = "Engine load"]
10460 pub engine_load: f32,
10461 #[doc = "Throttle position"]
10462 pub throttle_position: f32,
10463 #[doc = "Spark dwell time"]
10464 pub spark_dwell_time: f32,
10465 #[doc = "Barometric pressure"]
10466 pub barometric_pressure: f32,
10467 #[doc = "Intake manifold pressure("]
10468 pub intake_manifold_pressure: f32,
10469 #[doc = "Intake manifold temperature"]
10470 pub intake_manifold_temperature: f32,
10471 #[doc = "Cylinder head temperature"]
10472 pub cylinder_head_temperature: f32,
10473 #[doc = "Ignition timing (Crank angle degrees)"]
10474 pub ignition_timing: f32,
10475 #[doc = "Injection time"]
10476 pub injection_time: f32,
10477 #[doc = "Exhaust gas temperature"]
10478 pub exhaust_gas_temperature: f32,
10479 #[doc = "Output throttle"]
10480 pub throttle_out: f32,
10481 #[doc = "Pressure/temperature compensation"]
10482 pub pt_compensation: f32,
10483 #[doc = "EFI health status"]
10484 pub health: u8,
10485 #[doc = "Supply voltage to EFI sparking system. Zero in this value means \"unknown\", so if the supply voltage really is zero volts use 0.0001 instead."]
10486 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
10487 pub ignition_voltage: f32,
10488 #[doc = "Fuel pressure. Zero in this value means \"unknown\", so if the fuel pressure really is zero kPa use 0.0001 instead."]
10489 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
10490 pub fuel_pressure: f32,
10491}
10492impl EFI_STATUS_DATA {
10493 pub const ENCODED_LEN: usize = 73usize;
10494 pub const DEFAULT: Self = Self {
10495 ecu_index: 0.0_f32,
10496 rpm: 0.0_f32,
10497 fuel_consumed: 0.0_f32,
10498 fuel_flow: 0.0_f32,
10499 engine_load: 0.0_f32,
10500 throttle_position: 0.0_f32,
10501 spark_dwell_time: 0.0_f32,
10502 barometric_pressure: 0.0_f32,
10503 intake_manifold_pressure: 0.0_f32,
10504 intake_manifold_temperature: 0.0_f32,
10505 cylinder_head_temperature: 0.0_f32,
10506 ignition_timing: 0.0_f32,
10507 injection_time: 0.0_f32,
10508 exhaust_gas_temperature: 0.0_f32,
10509 throttle_out: 0.0_f32,
10510 pt_compensation: 0.0_f32,
10511 health: 0_u8,
10512 ignition_voltage: 0.0_f32,
10513 fuel_pressure: 0.0_f32,
10514 };
10515 #[cfg(feature = "arbitrary")]
10516 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10517 use arbitrary::{Arbitrary, Unstructured};
10518 let mut buf = [0u8; 1024];
10519 rng.fill_bytes(&mut buf);
10520 let mut unstructured = Unstructured::new(&buf);
10521 Self::arbitrary(&mut unstructured).unwrap_or_default()
10522 }
10523}
10524impl Default for EFI_STATUS_DATA {
10525 fn default() -> Self {
10526 Self::DEFAULT.clone()
10527 }
10528}
10529impl MessageData for EFI_STATUS_DATA {
10530 type Message = MavMessage;
10531 const ID: u32 = 225u32;
10532 const NAME: &'static str = "EFI_STATUS";
10533 const EXTRA_CRC: u8 = 208u8;
10534 const ENCODED_LEN: usize = 73usize;
10535 fn deser(
10536 _version: MavlinkVersion,
10537 __input: &[u8],
10538 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10539 let avail_len = __input.len();
10540 let mut payload_buf = [0; Self::ENCODED_LEN];
10541 let mut buf = if avail_len < Self::ENCODED_LEN {
10542 payload_buf[0..avail_len].copy_from_slice(__input);
10543 Bytes::new(&payload_buf)
10544 } else {
10545 Bytes::new(__input)
10546 };
10547 let mut __struct = Self::default();
10548 __struct.ecu_index = buf.get_f32_le();
10549 __struct.rpm = buf.get_f32_le();
10550 __struct.fuel_consumed = buf.get_f32_le();
10551 __struct.fuel_flow = buf.get_f32_le();
10552 __struct.engine_load = buf.get_f32_le();
10553 __struct.throttle_position = buf.get_f32_le();
10554 __struct.spark_dwell_time = buf.get_f32_le();
10555 __struct.barometric_pressure = buf.get_f32_le();
10556 __struct.intake_manifold_pressure = buf.get_f32_le();
10557 __struct.intake_manifold_temperature = buf.get_f32_le();
10558 __struct.cylinder_head_temperature = buf.get_f32_le();
10559 __struct.ignition_timing = buf.get_f32_le();
10560 __struct.injection_time = buf.get_f32_le();
10561 __struct.exhaust_gas_temperature = buf.get_f32_le();
10562 __struct.throttle_out = buf.get_f32_le();
10563 __struct.pt_compensation = buf.get_f32_le();
10564 __struct.health = buf.get_u8();
10565 __struct.ignition_voltage = buf.get_f32_le();
10566 __struct.fuel_pressure = buf.get_f32_le();
10567 Ok(__struct)
10568 }
10569 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10570 let mut __tmp = BytesMut::new(bytes);
10571 #[allow(clippy::absurd_extreme_comparisons)]
10572 #[allow(unused_comparisons)]
10573 if __tmp.remaining() < Self::ENCODED_LEN {
10574 panic!(
10575 "buffer is too small (need {} bytes, but got {})",
10576 Self::ENCODED_LEN,
10577 __tmp.remaining(),
10578 )
10579 }
10580 __tmp.put_f32_le(self.ecu_index);
10581 __tmp.put_f32_le(self.rpm);
10582 __tmp.put_f32_le(self.fuel_consumed);
10583 __tmp.put_f32_le(self.fuel_flow);
10584 __tmp.put_f32_le(self.engine_load);
10585 __tmp.put_f32_le(self.throttle_position);
10586 __tmp.put_f32_le(self.spark_dwell_time);
10587 __tmp.put_f32_le(self.barometric_pressure);
10588 __tmp.put_f32_le(self.intake_manifold_pressure);
10589 __tmp.put_f32_le(self.intake_manifold_temperature);
10590 __tmp.put_f32_le(self.cylinder_head_temperature);
10591 __tmp.put_f32_le(self.ignition_timing);
10592 __tmp.put_f32_le(self.injection_time);
10593 __tmp.put_f32_le(self.exhaust_gas_temperature);
10594 __tmp.put_f32_le(self.throttle_out);
10595 __tmp.put_f32_le(self.pt_compensation);
10596 __tmp.put_u8(self.health);
10597 __tmp.put_f32_le(self.ignition_voltage);
10598 __tmp.put_f32_le(self.fuel_pressure);
10599 if matches!(version, MavlinkVersion::V2) {
10600 let len = __tmp.len();
10601 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10602 } else {
10603 __tmp.len()
10604 }
10605 }
10606}
10607#[doc = "id: 131"]
10608#[doc = "Data packet for images sent using the Image Transmission Protocol: <https://mavlink.io/en/services/image_transmission.html>."]
10609#[derive(Debug, Clone, PartialEq)]
10610#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10611#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10612pub struct ENCAPSULATED_DATA_DATA {
10613 #[doc = "sequence number (starting with 0 on every transmission)"]
10614 pub seqnr: u16,
10615 #[doc = "image data bytes"]
10616 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10617 pub data: [u8; 253],
10618}
10619impl ENCAPSULATED_DATA_DATA {
10620 pub const ENCODED_LEN: usize = 255usize;
10621 pub const DEFAULT: Self = Self {
10622 seqnr: 0_u16,
10623 data: [0_u8; 253usize],
10624 };
10625 #[cfg(feature = "arbitrary")]
10626 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10627 use arbitrary::{Arbitrary, Unstructured};
10628 let mut buf = [0u8; 1024];
10629 rng.fill_bytes(&mut buf);
10630 let mut unstructured = Unstructured::new(&buf);
10631 Self::arbitrary(&mut unstructured).unwrap_or_default()
10632 }
10633}
10634impl Default for ENCAPSULATED_DATA_DATA {
10635 fn default() -> Self {
10636 Self::DEFAULT.clone()
10637 }
10638}
10639impl MessageData for ENCAPSULATED_DATA_DATA {
10640 type Message = MavMessage;
10641 const ID: u32 = 131u32;
10642 const NAME: &'static str = "ENCAPSULATED_DATA";
10643 const EXTRA_CRC: u8 = 223u8;
10644 const ENCODED_LEN: usize = 255usize;
10645 fn deser(
10646 _version: MavlinkVersion,
10647 __input: &[u8],
10648 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10649 let avail_len = __input.len();
10650 let mut payload_buf = [0; Self::ENCODED_LEN];
10651 let mut buf = if avail_len < Self::ENCODED_LEN {
10652 payload_buf[0..avail_len].copy_from_slice(__input);
10653 Bytes::new(&payload_buf)
10654 } else {
10655 Bytes::new(__input)
10656 };
10657 let mut __struct = Self::default();
10658 __struct.seqnr = buf.get_u16_le();
10659 for v in &mut __struct.data {
10660 let val = buf.get_u8();
10661 *v = val;
10662 }
10663 Ok(__struct)
10664 }
10665 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10666 let mut __tmp = BytesMut::new(bytes);
10667 #[allow(clippy::absurd_extreme_comparisons)]
10668 #[allow(unused_comparisons)]
10669 if __tmp.remaining() < Self::ENCODED_LEN {
10670 panic!(
10671 "buffer is too small (need {} bytes, but got {})",
10672 Self::ENCODED_LEN,
10673 __tmp.remaining(),
10674 )
10675 }
10676 __tmp.put_u16_le(self.seqnr);
10677 for val in &self.data {
10678 __tmp.put_u8(*val);
10679 }
10680 if matches!(version, MavlinkVersion::V2) {
10681 let len = __tmp.len();
10682 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10683 } else {
10684 __tmp.len()
10685 }
10686 }
10687}
10688#[doc = "id: 290"]
10689#[doc = "ESC information for lower rate streaming. Recommended streaming rate 1Hz. See ESC_STATUS for higher-rate ESC data."]
10690#[derive(Debug, Clone, PartialEq)]
10691#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10692#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10693pub struct ESC_INFO_DATA {
10694 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number."]
10695 pub time_usec: u64,
10696 #[doc = "Number of reported errors by each ESC since boot."]
10697 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10698 pub error_count: [u32; 4],
10699 #[doc = "Counter of data packets received."]
10700 pub counter: u16,
10701 #[doc = "Bitmap of ESC failure flags."]
10702 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10703 pub failure_flags: [u16; 4],
10704 #[doc = "Temperature of each ESC. INT16_MAX: if data not supplied by ESC."]
10705 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10706 pub temperature: [i16; 4],
10707 #[doc = "Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4."]
10708 pub index: u8,
10709 #[doc = "Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data."]
10710 pub count: u8,
10711 #[doc = "Connection type protocol for all ESC."]
10712 pub connection_type: EscConnectionType,
10713 #[doc = "Information regarding online/offline status of each ESC."]
10714 pub info: u8,
10715}
10716impl ESC_INFO_DATA {
10717 pub const ENCODED_LEN: usize = 46usize;
10718 pub const DEFAULT: Self = Self {
10719 time_usec: 0_u64,
10720 error_count: [0_u32; 4usize],
10721 counter: 0_u16,
10722 failure_flags: [0_u16; 4usize],
10723 temperature: [0_i16; 4usize],
10724 index: 0_u8,
10725 count: 0_u8,
10726 connection_type: EscConnectionType::DEFAULT,
10727 info: 0_u8,
10728 };
10729 #[cfg(feature = "arbitrary")]
10730 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10731 use arbitrary::{Arbitrary, Unstructured};
10732 let mut buf = [0u8; 1024];
10733 rng.fill_bytes(&mut buf);
10734 let mut unstructured = Unstructured::new(&buf);
10735 Self::arbitrary(&mut unstructured).unwrap_or_default()
10736 }
10737}
10738impl Default for ESC_INFO_DATA {
10739 fn default() -> Self {
10740 Self::DEFAULT.clone()
10741 }
10742}
10743impl MessageData for ESC_INFO_DATA {
10744 type Message = MavMessage;
10745 const ID: u32 = 290u32;
10746 const NAME: &'static str = "ESC_INFO";
10747 const EXTRA_CRC: u8 = 251u8;
10748 const ENCODED_LEN: usize = 46usize;
10749 fn deser(
10750 _version: MavlinkVersion,
10751 __input: &[u8],
10752 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10753 let avail_len = __input.len();
10754 let mut payload_buf = [0; Self::ENCODED_LEN];
10755 let mut buf = if avail_len < Self::ENCODED_LEN {
10756 payload_buf[0..avail_len].copy_from_slice(__input);
10757 Bytes::new(&payload_buf)
10758 } else {
10759 Bytes::new(__input)
10760 };
10761 let mut __struct = Self::default();
10762 __struct.time_usec = buf.get_u64_le();
10763 for v in &mut __struct.error_count {
10764 let val = buf.get_u32_le();
10765 *v = val;
10766 }
10767 __struct.counter = buf.get_u16_le();
10768 for v in &mut __struct.failure_flags {
10769 let val = buf.get_u16_le();
10770 *v = val;
10771 }
10772 for v in &mut __struct.temperature {
10773 let val = buf.get_i16_le();
10774 *v = val;
10775 }
10776 __struct.index = buf.get_u8();
10777 __struct.count = buf.get_u8();
10778 let tmp = buf.get_u8();
10779 __struct.connection_type =
10780 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10781 enum_type: "EscConnectionType",
10782 value: tmp as u32,
10783 })?;
10784 __struct.info = buf.get_u8();
10785 Ok(__struct)
10786 }
10787 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10788 let mut __tmp = BytesMut::new(bytes);
10789 #[allow(clippy::absurd_extreme_comparisons)]
10790 #[allow(unused_comparisons)]
10791 if __tmp.remaining() < Self::ENCODED_LEN {
10792 panic!(
10793 "buffer is too small (need {} bytes, but got {})",
10794 Self::ENCODED_LEN,
10795 __tmp.remaining(),
10796 )
10797 }
10798 __tmp.put_u64_le(self.time_usec);
10799 for val in &self.error_count {
10800 __tmp.put_u32_le(*val);
10801 }
10802 __tmp.put_u16_le(self.counter);
10803 for val in &self.failure_flags {
10804 __tmp.put_u16_le(*val);
10805 }
10806 for val in &self.temperature {
10807 __tmp.put_i16_le(*val);
10808 }
10809 __tmp.put_u8(self.index);
10810 __tmp.put_u8(self.count);
10811 __tmp.put_u8(self.connection_type as u8);
10812 __tmp.put_u8(self.info);
10813 if matches!(version, MavlinkVersion::V2) {
10814 let len = __tmp.len();
10815 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10816 } else {
10817 __tmp.len()
10818 }
10819 }
10820}
10821#[doc = "id: 291"]
10822#[doc = "ESC information for higher rate streaming. Recommended streaming rate is ~10 Hz. Information that changes more slowly is sent in ESC_INFO. It should typically only be streamed on high-bandwidth links (i.e. to a companion computer)."]
10823#[derive(Debug, Clone, PartialEq)]
10824#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10825#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10826pub struct ESC_STATUS_DATA {
10827 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number."]
10828 pub time_usec: u64,
10829 #[doc = "Reported motor RPM from each ESC (negative for reverse rotation)."]
10830 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10831 pub rpm: [i32; 4],
10832 #[doc = "Voltage measured from each ESC."]
10833 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10834 pub voltage: [f32; 4],
10835 #[doc = "Current measured from each ESC."]
10836 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10837 pub current: [f32; 4],
10838 #[doc = "Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4."]
10839 pub index: u8,
10840}
10841impl ESC_STATUS_DATA {
10842 pub const ENCODED_LEN: usize = 57usize;
10843 pub const DEFAULT: Self = Self {
10844 time_usec: 0_u64,
10845 rpm: [0_i32; 4usize],
10846 voltage: [0.0_f32; 4usize],
10847 current: [0.0_f32; 4usize],
10848 index: 0_u8,
10849 };
10850 #[cfg(feature = "arbitrary")]
10851 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10852 use arbitrary::{Arbitrary, Unstructured};
10853 let mut buf = [0u8; 1024];
10854 rng.fill_bytes(&mut buf);
10855 let mut unstructured = Unstructured::new(&buf);
10856 Self::arbitrary(&mut unstructured).unwrap_or_default()
10857 }
10858}
10859impl Default for ESC_STATUS_DATA {
10860 fn default() -> Self {
10861 Self::DEFAULT.clone()
10862 }
10863}
10864impl MessageData for ESC_STATUS_DATA {
10865 type Message = MavMessage;
10866 const ID: u32 = 291u32;
10867 const NAME: &'static str = "ESC_STATUS";
10868 const EXTRA_CRC: u8 = 10u8;
10869 const ENCODED_LEN: usize = 57usize;
10870 fn deser(
10871 _version: MavlinkVersion,
10872 __input: &[u8],
10873 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10874 let avail_len = __input.len();
10875 let mut payload_buf = [0; Self::ENCODED_LEN];
10876 let mut buf = if avail_len < Self::ENCODED_LEN {
10877 payload_buf[0..avail_len].copy_from_slice(__input);
10878 Bytes::new(&payload_buf)
10879 } else {
10880 Bytes::new(__input)
10881 };
10882 let mut __struct = Self::default();
10883 __struct.time_usec = buf.get_u64_le();
10884 for v in &mut __struct.rpm {
10885 let val = buf.get_i32_le();
10886 *v = val;
10887 }
10888 for v in &mut __struct.voltage {
10889 let val = buf.get_f32_le();
10890 *v = val;
10891 }
10892 for v in &mut __struct.current {
10893 let val = buf.get_f32_le();
10894 *v = val;
10895 }
10896 __struct.index = buf.get_u8();
10897 Ok(__struct)
10898 }
10899 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10900 let mut __tmp = BytesMut::new(bytes);
10901 #[allow(clippy::absurd_extreme_comparisons)]
10902 #[allow(unused_comparisons)]
10903 if __tmp.remaining() < Self::ENCODED_LEN {
10904 panic!(
10905 "buffer is too small (need {} bytes, but got {})",
10906 Self::ENCODED_LEN,
10907 __tmp.remaining(),
10908 )
10909 }
10910 __tmp.put_u64_le(self.time_usec);
10911 for val in &self.rpm {
10912 __tmp.put_i32_le(*val);
10913 }
10914 for val in &self.voltage {
10915 __tmp.put_f32_le(*val);
10916 }
10917 for val in &self.current {
10918 __tmp.put_f32_le(*val);
10919 }
10920 __tmp.put_u8(self.index);
10921 if matches!(version, MavlinkVersion::V2) {
10922 let len = __tmp.len();
10923 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10924 } else {
10925 __tmp.len()
10926 }
10927 }
10928}
10929#[doc = "id: 230"]
10930#[doc = "Estimator status message including flags, innovation test ratios and estimated accuracies. The flags message is an integer bitmask containing information on which EKF outputs are valid. See the ESTIMATOR_STATUS_FLAGS enum definition for further information. The innovation test ratios show the magnitude of the sensor innovation divided by the innovation check threshold. Under normal operation the innovation test ratios should be below 0.5 with occasional values up to 1.0. Values greater than 1.0 should be rare under normal operation and indicate that a measurement has been rejected by the filter. The user should be notified if an innovation test ratio greater than 1.0 is recorded. Notifications for values in the range between 0.5 and 1.0 should be optional and controllable by the user."]
10931#[derive(Debug, Clone, PartialEq)]
10932#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10933#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10934pub struct ESTIMATOR_STATUS_DATA {
10935 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
10936 pub time_usec: u64,
10937 #[doc = "Velocity innovation test ratio"]
10938 pub vel_ratio: f32,
10939 #[doc = "Horizontal position innovation test ratio"]
10940 pub pos_horiz_ratio: f32,
10941 #[doc = "Vertical position innovation test ratio"]
10942 pub pos_vert_ratio: f32,
10943 #[doc = "Magnetometer innovation test ratio"]
10944 pub mag_ratio: f32,
10945 #[doc = "Height above terrain innovation test ratio"]
10946 pub hagl_ratio: f32,
10947 #[doc = "True airspeed innovation test ratio"]
10948 pub tas_ratio: f32,
10949 #[doc = "Horizontal position 1-STD accuracy relative to the EKF local origin"]
10950 pub pos_horiz_accuracy: f32,
10951 #[doc = "Vertical position 1-STD accuracy relative to the EKF local origin"]
10952 pub pos_vert_accuracy: f32,
10953 #[doc = "Bitmap indicating which EKF outputs are valid."]
10954 pub flags: EstimatorStatusFlags,
10955}
10956impl ESTIMATOR_STATUS_DATA {
10957 pub const ENCODED_LEN: usize = 42usize;
10958 pub const DEFAULT: Self = Self {
10959 time_usec: 0_u64,
10960 vel_ratio: 0.0_f32,
10961 pos_horiz_ratio: 0.0_f32,
10962 pos_vert_ratio: 0.0_f32,
10963 mag_ratio: 0.0_f32,
10964 hagl_ratio: 0.0_f32,
10965 tas_ratio: 0.0_f32,
10966 pos_horiz_accuracy: 0.0_f32,
10967 pos_vert_accuracy: 0.0_f32,
10968 flags: EstimatorStatusFlags::DEFAULT,
10969 };
10970 #[cfg(feature = "arbitrary")]
10971 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10972 use arbitrary::{Arbitrary, Unstructured};
10973 let mut buf = [0u8; 1024];
10974 rng.fill_bytes(&mut buf);
10975 let mut unstructured = Unstructured::new(&buf);
10976 Self::arbitrary(&mut unstructured).unwrap_or_default()
10977 }
10978}
10979impl Default for ESTIMATOR_STATUS_DATA {
10980 fn default() -> Self {
10981 Self::DEFAULT.clone()
10982 }
10983}
10984impl MessageData for ESTIMATOR_STATUS_DATA {
10985 type Message = MavMessage;
10986 const ID: u32 = 230u32;
10987 const NAME: &'static str = "ESTIMATOR_STATUS";
10988 const EXTRA_CRC: u8 = 163u8;
10989 const ENCODED_LEN: usize = 42usize;
10990 fn deser(
10991 _version: MavlinkVersion,
10992 __input: &[u8],
10993 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10994 let avail_len = __input.len();
10995 let mut payload_buf = [0; Self::ENCODED_LEN];
10996 let mut buf = if avail_len < Self::ENCODED_LEN {
10997 payload_buf[0..avail_len].copy_from_slice(__input);
10998 Bytes::new(&payload_buf)
10999 } else {
11000 Bytes::new(__input)
11001 };
11002 let mut __struct = Self::default();
11003 __struct.time_usec = buf.get_u64_le();
11004 __struct.vel_ratio = buf.get_f32_le();
11005 __struct.pos_horiz_ratio = buf.get_f32_le();
11006 __struct.pos_vert_ratio = buf.get_f32_le();
11007 __struct.mag_ratio = buf.get_f32_le();
11008 __struct.hagl_ratio = buf.get_f32_le();
11009 __struct.tas_ratio = buf.get_f32_le();
11010 __struct.pos_horiz_accuracy = buf.get_f32_le();
11011 __struct.pos_vert_accuracy = buf.get_f32_le();
11012 let tmp = buf.get_u16_le();
11013 __struct.flags = EstimatorStatusFlags::from_bits(tmp & EstimatorStatusFlags::all().bits())
11014 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
11015 flag_type: "EstimatorStatusFlags",
11016 value: tmp as u32,
11017 })?;
11018 Ok(__struct)
11019 }
11020 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11021 let mut __tmp = BytesMut::new(bytes);
11022 #[allow(clippy::absurd_extreme_comparisons)]
11023 #[allow(unused_comparisons)]
11024 if __tmp.remaining() < Self::ENCODED_LEN {
11025 panic!(
11026 "buffer is too small (need {} bytes, but got {})",
11027 Self::ENCODED_LEN,
11028 __tmp.remaining(),
11029 )
11030 }
11031 __tmp.put_u64_le(self.time_usec);
11032 __tmp.put_f32_le(self.vel_ratio);
11033 __tmp.put_f32_le(self.pos_horiz_ratio);
11034 __tmp.put_f32_le(self.pos_vert_ratio);
11035 __tmp.put_f32_le(self.mag_ratio);
11036 __tmp.put_f32_le(self.hagl_ratio);
11037 __tmp.put_f32_le(self.tas_ratio);
11038 __tmp.put_f32_le(self.pos_horiz_accuracy);
11039 __tmp.put_f32_le(self.pos_vert_accuracy);
11040 __tmp.put_u16_le(self.flags.bits());
11041 if matches!(version, MavlinkVersion::V2) {
11042 let len = __tmp.len();
11043 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11044 } else {
11045 __tmp.len()
11046 }
11047 }
11048}
11049#[doc = "id: 410"]
11050#[doc = "Event message. Each new event from a particular component gets a new sequence number. The same message might be sent multiple times if (re-)requested. Most events are broadcast, some can be specific to a target component (as receivers keep track of the sequence for missed events, all events need to be broadcast. Thus we use destination_component instead of target_component)."]
11051#[derive(Debug, Clone, PartialEq)]
11052#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11053#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11054pub struct EVENT_DATA {
11055 #[doc = "Event ID (as defined in the component metadata)"]
11056 pub id: u32,
11057 #[doc = "Timestamp (time since system boot when the event happened)."]
11058 pub event_time_boot_ms: u32,
11059 #[doc = "Sequence number."]
11060 pub sequence: u16,
11061 #[doc = "Component ID"]
11062 pub destination_component: u8,
11063 #[doc = "System ID"]
11064 pub destination_system: u8,
11065 #[doc = "Log levels: 4 bits MSB: internal (for logging purposes), 4 bits LSB: external. Levels: Emergency = 0, Alert = 1, Critical = 2, Error = 3, Warning = 4, Notice = 5, Info = 6, Debug = 7, Protocol = 8, Disabled = 9"]
11066 pub log_levels: u8,
11067 #[doc = "Arguments (depend on event ID)."]
11068 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11069 pub arguments: [u8; 40],
11070}
11071impl EVENT_DATA {
11072 pub const ENCODED_LEN: usize = 53usize;
11073 pub const DEFAULT: Self = Self {
11074 id: 0_u32,
11075 event_time_boot_ms: 0_u32,
11076 sequence: 0_u16,
11077 destination_component: 0_u8,
11078 destination_system: 0_u8,
11079 log_levels: 0_u8,
11080 arguments: [0_u8; 40usize],
11081 };
11082 #[cfg(feature = "arbitrary")]
11083 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11084 use arbitrary::{Arbitrary, Unstructured};
11085 let mut buf = [0u8; 1024];
11086 rng.fill_bytes(&mut buf);
11087 let mut unstructured = Unstructured::new(&buf);
11088 Self::arbitrary(&mut unstructured).unwrap_or_default()
11089 }
11090}
11091impl Default for EVENT_DATA {
11092 fn default() -> Self {
11093 Self::DEFAULT.clone()
11094 }
11095}
11096impl MessageData for EVENT_DATA {
11097 type Message = MavMessage;
11098 const ID: u32 = 410u32;
11099 const NAME: &'static str = "EVENT";
11100 const EXTRA_CRC: u8 = 160u8;
11101 const ENCODED_LEN: usize = 53usize;
11102 fn deser(
11103 _version: MavlinkVersion,
11104 __input: &[u8],
11105 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11106 let avail_len = __input.len();
11107 let mut payload_buf = [0; Self::ENCODED_LEN];
11108 let mut buf = if avail_len < Self::ENCODED_LEN {
11109 payload_buf[0..avail_len].copy_from_slice(__input);
11110 Bytes::new(&payload_buf)
11111 } else {
11112 Bytes::new(__input)
11113 };
11114 let mut __struct = Self::default();
11115 __struct.id = buf.get_u32_le();
11116 __struct.event_time_boot_ms = buf.get_u32_le();
11117 __struct.sequence = buf.get_u16_le();
11118 __struct.destination_component = buf.get_u8();
11119 __struct.destination_system = buf.get_u8();
11120 __struct.log_levels = buf.get_u8();
11121 for v in &mut __struct.arguments {
11122 let val = buf.get_u8();
11123 *v = val;
11124 }
11125 Ok(__struct)
11126 }
11127 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11128 let mut __tmp = BytesMut::new(bytes);
11129 #[allow(clippy::absurd_extreme_comparisons)]
11130 #[allow(unused_comparisons)]
11131 if __tmp.remaining() < Self::ENCODED_LEN {
11132 panic!(
11133 "buffer is too small (need {} bytes, but got {})",
11134 Self::ENCODED_LEN,
11135 __tmp.remaining(),
11136 )
11137 }
11138 __tmp.put_u32_le(self.id);
11139 __tmp.put_u32_le(self.event_time_boot_ms);
11140 __tmp.put_u16_le(self.sequence);
11141 __tmp.put_u8(self.destination_component);
11142 __tmp.put_u8(self.destination_system);
11143 __tmp.put_u8(self.log_levels);
11144 for val in &self.arguments {
11145 __tmp.put_u8(*val);
11146 }
11147 if matches!(version, MavlinkVersion::V2) {
11148 let len = __tmp.len();
11149 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11150 } else {
11151 __tmp.len()
11152 }
11153 }
11154}
11155#[doc = "id: 245"]
11156#[doc = "Provides state for additional features."]
11157#[derive(Debug, Clone, PartialEq)]
11158#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11159#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11160pub struct EXTENDED_SYS_STATE_DATA {
11161 #[doc = "The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration."]
11162 pub vtol_state: MavVtolState,
11163 #[doc = "The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown."]
11164 pub landed_state: MavLandedState,
11165}
11166impl EXTENDED_SYS_STATE_DATA {
11167 pub const ENCODED_LEN: usize = 2usize;
11168 pub const DEFAULT: Self = Self {
11169 vtol_state: MavVtolState::DEFAULT,
11170 landed_state: MavLandedState::DEFAULT,
11171 };
11172 #[cfg(feature = "arbitrary")]
11173 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11174 use arbitrary::{Arbitrary, Unstructured};
11175 let mut buf = [0u8; 1024];
11176 rng.fill_bytes(&mut buf);
11177 let mut unstructured = Unstructured::new(&buf);
11178 Self::arbitrary(&mut unstructured).unwrap_or_default()
11179 }
11180}
11181impl Default for EXTENDED_SYS_STATE_DATA {
11182 fn default() -> Self {
11183 Self::DEFAULT.clone()
11184 }
11185}
11186impl MessageData for EXTENDED_SYS_STATE_DATA {
11187 type Message = MavMessage;
11188 const ID: u32 = 245u32;
11189 const NAME: &'static str = "EXTENDED_SYS_STATE";
11190 const EXTRA_CRC: u8 = 130u8;
11191 const ENCODED_LEN: usize = 2usize;
11192 fn deser(
11193 _version: MavlinkVersion,
11194 __input: &[u8],
11195 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11196 let avail_len = __input.len();
11197 let mut payload_buf = [0; Self::ENCODED_LEN];
11198 let mut buf = if avail_len < Self::ENCODED_LEN {
11199 payload_buf[0..avail_len].copy_from_slice(__input);
11200 Bytes::new(&payload_buf)
11201 } else {
11202 Bytes::new(__input)
11203 };
11204 let mut __struct = Self::default();
11205 let tmp = buf.get_u8();
11206 __struct.vtol_state =
11207 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11208 enum_type: "MavVtolState",
11209 value: tmp as u32,
11210 })?;
11211 let tmp = buf.get_u8();
11212 __struct.landed_state =
11213 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11214 enum_type: "MavLandedState",
11215 value: tmp as u32,
11216 })?;
11217 Ok(__struct)
11218 }
11219 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11220 let mut __tmp = BytesMut::new(bytes);
11221 #[allow(clippy::absurd_extreme_comparisons)]
11222 #[allow(unused_comparisons)]
11223 if __tmp.remaining() < Self::ENCODED_LEN {
11224 panic!(
11225 "buffer is too small (need {} bytes, but got {})",
11226 Self::ENCODED_LEN,
11227 __tmp.remaining(),
11228 )
11229 }
11230 __tmp.put_u8(self.vtol_state as u8);
11231 __tmp.put_u8(self.landed_state as u8);
11232 if matches!(version, MavlinkVersion::V2) {
11233 let len = __tmp.len();
11234 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11235 } else {
11236 __tmp.len()
11237 }
11238 }
11239}
11240#[doc = "id: 162"]
11241#[doc = "Status of geo-fencing. Sent in extended status stream when fencing enabled."]
11242#[derive(Debug, Clone, PartialEq)]
11243#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11244#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11245pub struct FENCE_STATUS_DATA {
11246 #[doc = "Time (since boot) of last breach."]
11247 pub breach_time: u32,
11248 #[doc = "Number of fence breaches."]
11249 pub breach_count: u16,
11250 #[doc = "Breach status (0 if currently inside fence, 1 if outside)."]
11251 pub breach_status: u8,
11252 #[doc = "Last breach type."]
11253 pub breach_type: FenceBreach,
11254 #[doc = "Active action to prevent fence breach"]
11255 #[cfg_attr(feature = "serde", serde(default))]
11256 pub breach_mitigation: FenceMitigate,
11257}
11258impl FENCE_STATUS_DATA {
11259 pub const ENCODED_LEN: usize = 9usize;
11260 pub const DEFAULT: Self = Self {
11261 breach_time: 0_u32,
11262 breach_count: 0_u16,
11263 breach_status: 0_u8,
11264 breach_type: FenceBreach::DEFAULT,
11265 breach_mitigation: FenceMitigate::DEFAULT,
11266 };
11267 #[cfg(feature = "arbitrary")]
11268 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11269 use arbitrary::{Arbitrary, Unstructured};
11270 let mut buf = [0u8; 1024];
11271 rng.fill_bytes(&mut buf);
11272 let mut unstructured = Unstructured::new(&buf);
11273 Self::arbitrary(&mut unstructured).unwrap_or_default()
11274 }
11275}
11276impl Default for FENCE_STATUS_DATA {
11277 fn default() -> Self {
11278 Self::DEFAULT.clone()
11279 }
11280}
11281impl MessageData for FENCE_STATUS_DATA {
11282 type Message = MavMessage;
11283 const ID: u32 = 162u32;
11284 const NAME: &'static str = "FENCE_STATUS";
11285 const EXTRA_CRC: u8 = 189u8;
11286 const ENCODED_LEN: usize = 9usize;
11287 fn deser(
11288 _version: MavlinkVersion,
11289 __input: &[u8],
11290 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11291 let avail_len = __input.len();
11292 let mut payload_buf = [0; Self::ENCODED_LEN];
11293 let mut buf = if avail_len < Self::ENCODED_LEN {
11294 payload_buf[0..avail_len].copy_from_slice(__input);
11295 Bytes::new(&payload_buf)
11296 } else {
11297 Bytes::new(__input)
11298 };
11299 let mut __struct = Self::default();
11300 __struct.breach_time = buf.get_u32_le();
11301 __struct.breach_count = buf.get_u16_le();
11302 __struct.breach_status = buf.get_u8();
11303 let tmp = buf.get_u8();
11304 __struct.breach_type =
11305 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11306 enum_type: "FenceBreach",
11307 value: tmp as u32,
11308 })?;
11309 let tmp = buf.get_u8();
11310 __struct.breach_mitigation =
11311 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11312 enum_type: "FenceMitigate",
11313 value: tmp as u32,
11314 })?;
11315 Ok(__struct)
11316 }
11317 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11318 let mut __tmp = BytesMut::new(bytes);
11319 #[allow(clippy::absurd_extreme_comparisons)]
11320 #[allow(unused_comparisons)]
11321 if __tmp.remaining() < Self::ENCODED_LEN {
11322 panic!(
11323 "buffer is too small (need {} bytes, but got {})",
11324 Self::ENCODED_LEN,
11325 __tmp.remaining(),
11326 )
11327 }
11328 __tmp.put_u32_le(self.breach_time);
11329 __tmp.put_u16_le(self.breach_count);
11330 __tmp.put_u8(self.breach_status);
11331 __tmp.put_u8(self.breach_type as u8);
11332 __tmp.put_u8(self.breach_mitigation as u8);
11333 if matches!(version, MavlinkVersion::V2) {
11334 let len = __tmp.len();
11335 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11336 } else {
11337 __tmp.len()
11338 }
11339 }
11340}
11341#[doc = "id: 110"]
11342#[doc = "File transfer protocol message: <https://mavlink.io/en/services/ftp.html>."]
11343#[derive(Debug, Clone, PartialEq)]
11344#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11345#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11346pub struct FILE_TRANSFER_PROTOCOL_DATA {
11347 #[doc = "Network ID (0 for broadcast)"]
11348 pub target_network: u8,
11349 #[doc = "System ID (0 for broadcast)"]
11350 pub target_system: u8,
11351 #[doc = "Component ID (0 for broadcast)"]
11352 pub target_component: u8,
11353 #[doc = "Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The content/format of this block is defined in <https://mavlink.io/en/services/ftp.html>."]
11354 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11355 pub payload: [u8; 251],
11356}
11357impl FILE_TRANSFER_PROTOCOL_DATA {
11358 pub const ENCODED_LEN: usize = 254usize;
11359 pub const DEFAULT: Self = Self {
11360 target_network: 0_u8,
11361 target_system: 0_u8,
11362 target_component: 0_u8,
11363 payload: [0_u8; 251usize],
11364 };
11365 #[cfg(feature = "arbitrary")]
11366 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11367 use arbitrary::{Arbitrary, Unstructured};
11368 let mut buf = [0u8; 1024];
11369 rng.fill_bytes(&mut buf);
11370 let mut unstructured = Unstructured::new(&buf);
11371 Self::arbitrary(&mut unstructured).unwrap_or_default()
11372 }
11373}
11374impl Default for FILE_TRANSFER_PROTOCOL_DATA {
11375 fn default() -> Self {
11376 Self::DEFAULT.clone()
11377 }
11378}
11379impl MessageData for FILE_TRANSFER_PROTOCOL_DATA {
11380 type Message = MavMessage;
11381 const ID: u32 = 110u32;
11382 const NAME: &'static str = "FILE_TRANSFER_PROTOCOL";
11383 const EXTRA_CRC: u8 = 84u8;
11384 const ENCODED_LEN: usize = 254usize;
11385 fn deser(
11386 _version: MavlinkVersion,
11387 __input: &[u8],
11388 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11389 let avail_len = __input.len();
11390 let mut payload_buf = [0; Self::ENCODED_LEN];
11391 let mut buf = if avail_len < Self::ENCODED_LEN {
11392 payload_buf[0..avail_len].copy_from_slice(__input);
11393 Bytes::new(&payload_buf)
11394 } else {
11395 Bytes::new(__input)
11396 };
11397 let mut __struct = Self::default();
11398 __struct.target_network = buf.get_u8();
11399 __struct.target_system = buf.get_u8();
11400 __struct.target_component = buf.get_u8();
11401 for v in &mut __struct.payload {
11402 let val = buf.get_u8();
11403 *v = val;
11404 }
11405 Ok(__struct)
11406 }
11407 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11408 let mut __tmp = BytesMut::new(bytes);
11409 #[allow(clippy::absurd_extreme_comparisons)]
11410 #[allow(unused_comparisons)]
11411 if __tmp.remaining() < Self::ENCODED_LEN {
11412 panic!(
11413 "buffer is too small (need {} bytes, but got {})",
11414 Self::ENCODED_LEN,
11415 __tmp.remaining(),
11416 )
11417 }
11418 __tmp.put_u8(self.target_network);
11419 __tmp.put_u8(self.target_system);
11420 __tmp.put_u8(self.target_component);
11421 for val in &self.payload {
11422 __tmp.put_u8(*val);
11423 }
11424 if matches!(version, MavlinkVersion::V2) {
11425 let len = __tmp.len();
11426 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11427 } else {
11428 __tmp.len()
11429 }
11430 }
11431}
11432#[doc = "id: 264"]
11433#[doc = "Flight information. This includes time since boot for arm, takeoff, and land, and a flight number. Takeoff and landing values reset to zero on arm. This can be requested using MAV_CMD_REQUEST_MESSAGE. Note, some fields are misnamed - timestamps are from boot (not UTC) and the flight_uuid is a sequence number."]
11434#[derive(Debug, Clone, PartialEq)]
11435#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11436#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11437pub struct FLIGHT_INFORMATION_DATA {
11438 #[doc = "Timestamp at arming (since system boot). Set to 0 on boot. Set value on arming. Note, field is misnamed UTC."]
11439 pub arming_time_utc: u64,
11440 #[doc = "Timestamp at takeoff (since system boot). Set to 0 at boot and on arming. Note, field is misnamed UTC."]
11441 pub takeoff_time_utc: u64,
11442 #[doc = "Flight number. Note, field is misnamed UUID."]
11443 pub flight_uuid: u64,
11444 #[doc = "Timestamp (time since system boot)."]
11445 pub time_boot_ms: u32,
11446 #[doc = "Timestamp at landing (in ms since system boot). Set to 0 at boot and on arming."]
11447 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
11448 pub landing_time: u32,
11449}
11450impl FLIGHT_INFORMATION_DATA {
11451 pub const ENCODED_LEN: usize = 32usize;
11452 pub const DEFAULT: Self = Self {
11453 arming_time_utc: 0_u64,
11454 takeoff_time_utc: 0_u64,
11455 flight_uuid: 0_u64,
11456 time_boot_ms: 0_u32,
11457 landing_time: 0_u32,
11458 };
11459 #[cfg(feature = "arbitrary")]
11460 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11461 use arbitrary::{Arbitrary, Unstructured};
11462 let mut buf = [0u8; 1024];
11463 rng.fill_bytes(&mut buf);
11464 let mut unstructured = Unstructured::new(&buf);
11465 Self::arbitrary(&mut unstructured).unwrap_or_default()
11466 }
11467}
11468impl Default for FLIGHT_INFORMATION_DATA {
11469 fn default() -> Self {
11470 Self::DEFAULT.clone()
11471 }
11472}
11473impl MessageData for FLIGHT_INFORMATION_DATA {
11474 type Message = MavMessage;
11475 const ID: u32 = 264u32;
11476 const NAME: &'static str = "FLIGHT_INFORMATION";
11477 const EXTRA_CRC: u8 = 49u8;
11478 const ENCODED_LEN: usize = 32usize;
11479 fn deser(
11480 _version: MavlinkVersion,
11481 __input: &[u8],
11482 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11483 let avail_len = __input.len();
11484 let mut payload_buf = [0; Self::ENCODED_LEN];
11485 let mut buf = if avail_len < Self::ENCODED_LEN {
11486 payload_buf[0..avail_len].copy_from_slice(__input);
11487 Bytes::new(&payload_buf)
11488 } else {
11489 Bytes::new(__input)
11490 };
11491 let mut __struct = Self::default();
11492 __struct.arming_time_utc = buf.get_u64_le();
11493 __struct.takeoff_time_utc = buf.get_u64_le();
11494 __struct.flight_uuid = buf.get_u64_le();
11495 __struct.time_boot_ms = buf.get_u32_le();
11496 __struct.landing_time = buf.get_u32_le();
11497 Ok(__struct)
11498 }
11499 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11500 let mut __tmp = BytesMut::new(bytes);
11501 #[allow(clippy::absurd_extreme_comparisons)]
11502 #[allow(unused_comparisons)]
11503 if __tmp.remaining() < Self::ENCODED_LEN {
11504 panic!(
11505 "buffer is too small (need {} bytes, but got {})",
11506 Self::ENCODED_LEN,
11507 __tmp.remaining(),
11508 )
11509 }
11510 __tmp.put_u64_le(self.arming_time_utc);
11511 __tmp.put_u64_le(self.takeoff_time_utc);
11512 __tmp.put_u64_le(self.flight_uuid);
11513 __tmp.put_u32_le(self.time_boot_ms);
11514 __tmp.put_u32_le(self.landing_time);
11515 if matches!(version, MavlinkVersion::V2) {
11516 let len = __tmp.len();
11517 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11518 } else {
11519 __tmp.len()
11520 }
11521 }
11522}
11523#[doc = "id: 144"]
11524#[doc = "Current motion information from a designated system."]
11525#[derive(Debug, Clone, PartialEq)]
11526#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11527#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11528pub struct FOLLOW_TARGET_DATA {
11529 #[doc = "Timestamp (time since system boot)."]
11530 pub timestamp: u64,
11531 #[doc = "button states or switches of a tracker device"]
11532 pub custom_state: u64,
11533 #[doc = "Latitude (WGS84)"]
11534 pub lat: i32,
11535 #[doc = "Longitude (WGS84)"]
11536 pub lon: i32,
11537 #[doc = "Altitude (MSL)"]
11538 pub alt: f32,
11539 #[doc = "target velocity (0,0,0) for unknown"]
11540 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11541 pub vel: [f32; 3],
11542 #[doc = "linear target acceleration (0,0,0) for unknown"]
11543 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11544 pub acc: [f32; 3],
11545 #[doc = "(0 0 0 0 for unknown)"]
11546 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11547 pub attitude_q: [f32; 4],
11548 #[doc = "(0 0 0 for unknown)"]
11549 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11550 pub rates: [f32; 3],
11551 #[doc = "eph epv"]
11552 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11553 pub position_cov: [f32; 3],
11554 #[doc = "bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)"]
11555 pub est_capabilities: u8,
11556}
11557impl FOLLOW_TARGET_DATA {
11558 pub const ENCODED_LEN: usize = 93usize;
11559 pub const DEFAULT: Self = Self {
11560 timestamp: 0_u64,
11561 custom_state: 0_u64,
11562 lat: 0_i32,
11563 lon: 0_i32,
11564 alt: 0.0_f32,
11565 vel: [0.0_f32; 3usize],
11566 acc: [0.0_f32; 3usize],
11567 attitude_q: [0.0_f32; 4usize],
11568 rates: [0.0_f32; 3usize],
11569 position_cov: [0.0_f32; 3usize],
11570 est_capabilities: 0_u8,
11571 };
11572 #[cfg(feature = "arbitrary")]
11573 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11574 use arbitrary::{Arbitrary, Unstructured};
11575 let mut buf = [0u8; 1024];
11576 rng.fill_bytes(&mut buf);
11577 let mut unstructured = Unstructured::new(&buf);
11578 Self::arbitrary(&mut unstructured).unwrap_or_default()
11579 }
11580}
11581impl Default for FOLLOW_TARGET_DATA {
11582 fn default() -> Self {
11583 Self::DEFAULT.clone()
11584 }
11585}
11586impl MessageData for FOLLOW_TARGET_DATA {
11587 type Message = MavMessage;
11588 const ID: u32 = 144u32;
11589 const NAME: &'static str = "FOLLOW_TARGET";
11590 const EXTRA_CRC: u8 = 127u8;
11591 const ENCODED_LEN: usize = 93usize;
11592 fn deser(
11593 _version: MavlinkVersion,
11594 __input: &[u8],
11595 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11596 let avail_len = __input.len();
11597 let mut payload_buf = [0; Self::ENCODED_LEN];
11598 let mut buf = if avail_len < Self::ENCODED_LEN {
11599 payload_buf[0..avail_len].copy_from_slice(__input);
11600 Bytes::new(&payload_buf)
11601 } else {
11602 Bytes::new(__input)
11603 };
11604 let mut __struct = Self::default();
11605 __struct.timestamp = buf.get_u64_le();
11606 __struct.custom_state = buf.get_u64_le();
11607 __struct.lat = buf.get_i32_le();
11608 __struct.lon = buf.get_i32_le();
11609 __struct.alt = buf.get_f32_le();
11610 for v in &mut __struct.vel {
11611 let val = buf.get_f32_le();
11612 *v = val;
11613 }
11614 for v in &mut __struct.acc {
11615 let val = buf.get_f32_le();
11616 *v = val;
11617 }
11618 for v in &mut __struct.attitude_q {
11619 let val = buf.get_f32_le();
11620 *v = val;
11621 }
11622 for v in &mut __struct.rates {
11623 let val = buf.get_f32_le();
11624 *v = val;
11625 }
11626 for v in &mut __struct.position_cov {
11627 let val = buf.get_f32_le();
11628 *v = val;
11629 }
11630 __struct.est_capabilities = buf.get_u8();
11631 Ok(__struct)
11632 }
11633 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11634 let mut __tmp = BytesMut::new(bytes);
11635 #[allow(clippy::absurd_extreme_comparisons)]
11636 #[allow(unused_comparisons)]
11637 if __tmp.remaining() < Self::ENCODED_LEN {
11638 panic!(
11639 "buffer is too small (need {} bytes, but got {})",
11640 Self::ENCODED_LEN,
11641 __tmp.remaining(),
11642 )
11643 }
11644 __tmp.put_u64_le(self.timestamp);
11645 __tmp.put_u64_le(self.custom_state);
11646 __tmp.put_i32_le(self.lat);
11647 __tmp.put_i32_le(self.lon);
11648 __tmp.put_f32_le(self.alt);
11649 for val in &self.vel {
11650 __tmp.put_f32_le(*val);
11651 }
11652 for val in &self.acc {
11653 __tmp.put_f32_le(*val);
11654 }
11655 for val in &self.attitude_q {
11656 __tmp.put_f32_le(*val);
11657 }
11658 for val in &self.rates {
11659 __tmp.put_f32_le(*val);
11660 }
11661 for val in &self.position_cov {
11662 __tmp.put_f32_le(*val);
11663 }
11664 __tmp.put_u8(self.est_capabilities);
11665 if matches!(version, MavlinkVersion::V2) {
11666 let len = __tmp.len();
11667 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11668 } else {
11669 __tmp.len()
11670 }
11671 }
11672}
11673#[doc = "id: 371"]
11674#[doc = "Fuel status. This message provides \"generic\" fuel level information for in a GCS and for triggering failsafes in an autopilot. The fuel type and associated units for fields in this message are defined in the enum MAV_FUEL_TYPE. The reported `consumed_fuel` and `remaining_fuel` must only be supplied if measured: they must not be inferred from the `maximum_fuel` and the other value. A recipient can assume that if these fields are supplied they are accurate. If not provided, the recipient can infer `remaining_fuel` from `maximum_fuel` and `consumed_fuel` on the assumption that the fuel was initially at its maximum (this is what battery monitors assume). Note however that this is an assumption, and the UI should prompt the user appropriately (i.e. notify user that they should fill the tank before boot). This kind of information may also be sent in fuel-specific messages such as BATTERY_STATUS_V2. If both messages are sent for the same fuel system, the ids and corresponding information must match. This should be streamed (nominally at 0.1 Hz)."]
11675#[derive(Debug, Clone, PartialEq)]
11676#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11677#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11678pub struct FUEL_STATUS_DATA {
11679 #[doc = "Capacity when full. Must be provided."]
11680 pub maximum_fuel: f32,
11681 #[doc = "Consumed fuel (measured). This value should not be inferred: if not measured set to NaN. NaN: field not provided."]
11682 pub consumed_fuel: f32,
11683 #[doc = "Remaining fuel until empty (measured). The value should not be inferred: if not measured set to NaN. NaN: field not provided."]
11684 pub remaining_fuel: f32,
11685 #[doc = "Positive value when emptying/using, and negative if filling/replacing. NaN: field not provided."]
11686 pub flow_rate: f32,
11687 #[doc = "Fuel temperature. NaN: field not provided."]
11688 pub temperature: f32,
11689 #[doc = "Fuel type. Defines units for fuel capacity and consumption fields above."]
11690 pub fuel_type: MavFuelType,
11691 #[doc = "Fuel ID. Must match ID of other messages for same fuel system, such as BATTERY_STATUS_V2."]
11692 pub id: u8,
11693 #[doc = "Percentage of remaining fuel, relative to full. Values: [0-100], UINT8_MAX: field not provided."]
11694 pub percent_remaining: u8,
11695}
11696impl FUEL_STATUS_DATA {
11697 pub const ENCODED_LEN: usize = 26usize;
11698 pub const DEFAULT: Self = Self {
11699 maximum_fuel: 0.0_f32,
11700 consumed_fuel: 0.0_f32,
11701 remaining_fuel: 0.0_f32,
11702 flow_rate: 0.0_f32,
11703 temperature: 0.0_f32,
11704 fuel_type: MavFuelType::DEFAULT,
11705 id: 0_u8,
11706 percent_remaining: 0_u8,
11707 };
11708 #[cfg(feature = "arbitrary")]
11709 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11710 use arbitrary::{Arbitrary, Unstructured};
11711 let mut buf = [0u8; 1024];
11712 rng.fill_bytes(&mut buf);
11713 let mut unstructured = Unstructured::new(&buf);
11714 Self::arbitrary(&mut unstructured).unwrap_or_default()
11715 }
11716}
11717impl Default for FUEL_STATUS_DATA {
11718 fn default() -> Self {
11719 Self::DEFAULT.clone()
11720 }
11721}
11722impl MessageData for FUEL_STATUS_DATA {
11723 type Message = MavMessage;
11724 const ID: u32 = 371u32;
11725 const NAME: &'static str = "FUEL_STATUS";
11726 const EXTRA_CRC: u8 = 10u8;
11727 const ENCODED_LEN: usize = 26usize;
11728 fn deser(
11729 _version: MavlinkVersion,
11730 __input: &[u8],
11731 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11732 let avail_len = __input.len();
11733 let mut payload_buf = [0; Self::ENCODED_LEN];
11734 let mut buf = if avail_len < Self::ENCODED_LEN {
11735 payload_buf[0..avail_len].copy_from_slice(__input);
11736 Bytes::new(&payload_buf)
11737 } else {
11738 Bytes::new(__input)
11739 };
11740 let mut __struct = Self::default();
11741 __struct.maximum_fuel = buf.get_f32_le();
11742 __struct.consumed_fuel = buf.get_f32_le();
11743 __struct.remaining_fuel = buf.get_f32_le();
11744 __struct.flow_rate = buf.get_f32_le();
11745 __struct.temperature = buf.get_f32_le();
11746 let tmp = buf.get_u32_le();
11747 __struct.fuel_type = FromPrimitive::from_u32(tmp).ok_or(
11748 ::mavlink_core::error::ParserError::InvalidEnum {
11749 enum_type: "MavFuelType",
11750 value: tmp as u32,
11751 },
11752 )?;
11753 __struct.id = buf.get_u8();
11754 __struct.percent_remaining = buf.get_u8();
11755 Ok(__struct)
11756 }
11757 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11758 let mut __tmp = BytesMut::new(bytes);
11759 #[allow(clippy::absurd_extreme_comparisons)]
11760 #[allow(unused_comparisons)]
11761 if __tmp.remaining() < Self::ENCODED_LEN {
11762 panic!(
11763 "buffer is too small (need {} bytes, but got {})",
11764 Self::ENCODED_LEN,
11765 __tmp.remaining(),
11766 )
11767 }
11768 __tmp.put_f32_le(self.maximum_fuel);
11769 __tmp.put_f32_le(self.consumed_fuel);
11770 __tmp.put_f32_le(self.remaining_fuel);
11771 __tmp.put_f32_le(self.flow_rate);
11772 __tmp.put_f32_le(self.temperature);
11773 __tmp.put_u32_le(self.fuel_type as u32);
11774 __tmp.put_u8(self.id);
11775 __tmp.put_u8(self.percent_remaining);
11776 if matches!(version, MavlinkVersion::V2) {
11777 let len = __tmp.len();
11778 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11779 } else {
11780 __tmp.len()
11781 }
11782 }
11783}
11784#[doc = "id: 373"]
11785#[doc = "Telemetry of power generation system. Alternator or mechanical generator."]
11786#[derive(Debug, Clone, PartialEq)]
11787#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11788#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11789pub struct GENERATOR_STATUS_DATA {
11790 #[doc = "Status flags."]
11791 pub status: MavGeneratorStatusFlag,
11792 #[doc = "Current into/out of battery. Positive for out. Negative for in. NaN: field not provided."]
11793 pub battery_current: f32,
11794 #[doc = "Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided"]
11795 pub load_current: f32,
11796 #[doc = "The power being generated. NaN: field not provided"]
11797 pub power_generated: f32,
11798 #[doc = "Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus."]
11799 pub bus_voltage: f32,
11800 #[doc = "The target battery current. Positive for out. Negative for in. NaN: field not provided"]
11801 pub bat_current_setpoint: f32,
11802 #[doc = "Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided."]
11803 pub runtime: u32,
11804 #[doc = "Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided."]
11805 pub time_until_maintenance: i32,
11806 #[doc = "Speed of electrical generator or alternator. UINT16_MAX: field not provided."]
11807 pub generator_speed: u16,
11808 #[doc = "The temperature of the rectifier or power converter. INT16_MAX: field not provided."]
11809 pub rectifier_temperature: i16,
11810 #[doc = "The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided."]
11811 pub generator_temperature: i16,
11812}
11813impl GENERATOR_STATUS_DATA {
11814 pub const ENCODED_LEN: usize = 42usize;
11815 pub const DEFAULT: Self = Self {
11816 status: MavGeneratorStatusFlag::DEFAULT,
11817 battery_current: 0.0_f32,
11818 load_current: 0.0_f32,
11819 power_generated: 0.0_f32,
11820 bus_voltage: 0.0_f32,
11821 bat_current_setpoint: 0.0_f32,
11822 runtime: 0_u32,
11823 time_until_maintenance: 0_i32,
11824 generator_speed: 0_u16,
11825 rectifier_temperature: 0_i16,
11826 generator_temperature: 0_i16,
11827 };
11828 #[cfg(feature = "arbitrary")]
11829 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11830 use arbitrary::{Arbitrary, Unstructured};
11831 let mut buf = [0u8; 1024];
11832 rng.fill_bytes(&mut buf);
11833 let mut unstructured = Unstructured::new(&buf);
11834 Self::arbitrary(&mut unstructured).unwrap_or_default()
11835 }
11836}
11837impl Default for GENERATOR_STATUS_DATA {
11838 fn default() -> Self {
11839 Self::DEFAULT.clone()
11840 }
11841}
11842impl MessageData for GENERATOR_STATUS_DATA {
11843 type Message = MavMessage;
11844 const ID: u32 = 373u32;
11845 const NAME: &'static str = "GENERATOR_STATUS";
11846 const EXTRA_CRC: u8 = 117u8;
11847 const ENCODED_LEN: usize = 42usize;
11848 fn deser(
11849 _version: MavlinkVersion,
11850 __input: &[u8],
11851 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11852 let avail_len = __input.len();
11853 let mut payload_buf = [0; Self::ENCODED_LEN];
11854 let mut buf = if avail_len < Self::ENCODED_LEN {
11855 payload_buf[0..avail_len].copy_from_slice(__input);
11856 Bytes::new(&payload_buf)
11857 } else {
11858 Bytes::new(__input)
11859 };
11860 let mut __struct = Self::default();
11861 let tmp = buf.get_u64_le();
11862 __struct.status = MavGeneratorStatusFlag::from_bits(
11863 tmp & MavGeneratorStatusFlag::all().bits(),
11864 )
11865 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
11866 flag_type: "MavGeneratorStatusFlag",
11867 value: tmp as u32,
11868 })?;
11869 __struct.battery_current = buf.get_f32_le();
11870 __struct.load_current = buf.get_f32_le();
11871 __struct.power_generated = buf.get_f32_le();
11872 __struct.bus_voltage = buf.get_f32_le();
11873 __struct.bat_current_setpoint = buf.get_f32_le();
11874 __struct.runtime = buf.get_u32_le();
11875 __struct.time_until_maintenance = buf.get_i32_le();
11876 __struct.generator_speed = buf.get_u16_le();
11877 __struct.rectifier_temperature = buf.get_i16_le();
11878 __struct.generator_temperature = buf.get_i16_le();
11879 Ok(__struct)
11880 }
11881 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11882 let mut __tmp = BytesMut::new(bytes);
11883 #[allow(clippy::absurd_extreme_comparisons)]
11884 #[allow(unused_comparisons)]
11885 if __tmp.remaining() < Self::ENCODED_LEN {
11886 panic!(
11887 "buffer is too small (need {} bytes, but got {})",
11888 Self::ENCODED_LEN,
11889 __tmp.remaining(),
11890 )
11891 }
11892 __tmp.put_u64_le(self.status.bits());
11893 __tmp.put_f32_le(self.battery_current);
11894 __tmp.put_f32_le(self.load_current);
11895 __tmp.put_f32_le(self.power_generated);
11896 __tmp.put_f32_le(self.bus_voltage);
11897 __tmp.put_f32_le(self.bat_current_setpoint);
11898 __tmp.put_u32_le(self.runtime);
11899 __tmp.put_i32_le(self.time_until_maintenance);
11900 __tmp.put_u16_le(self.generator_speed);
11901 __tmp.put_i16_le(self.rectifier_temperature);
11902 __tmp.put_i16_le(self.generator_temperature);
11903 if matches!(version, MavlinkVersion::V2) {
11904 let len = __tmp.len();
11905 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11906 } else {
11907 __tmp.len()
11908 }
11909 }
11910}
11911#[doc = "id: 285"]
11912#[doc = "Message reporting the status of a gimbal device. \t This message should be broadcast by a gimbal device component at a low regular rate (e.g. 5 Hz). \t For the angles encoded in the quaternion and the angular velocities holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). \t If neither of these flags are set, then (for backwards compatibility) it holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), \t else they are relative to the vehicle heading (vehicle frame). \t Other conditions of the flags are not allowed. \t The quaternion and angular velocities in the other frame can be calculated from delta_yaw and delta_yaw_velocity as \t q_earth = q_delta_yaw * q_vehicle and w_earth = w_delta_yaw_velocity + w_vehicle (if not NaN). \t If neither the GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME nor the GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME flag is set, \t then (for backwards compatibility) the data in the delta_yaw and delta_yaw_velocity fields are to be ignored. \t New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME, \t and always should set delta_yaw and delta_yaw_velocity either to the proper value or NaN."]
11913#[derive(Debug, Clone, PartialEq)]
11914#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11915#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11916pub struct GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
11917 #[doc = "Timestamp (time since system boot)."]
11918 pub time_boot_ms: u32,
11919 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description."]
11920 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11921 pub q: [f32; 4],
11922 #[doc = "X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN if unknown."]
11923 pub angular_velocity_x: f32,
11924 #[doc = "Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN if unknown."]
11925 pub angular_velocity_y: f32,
11926 #[doc = "Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN if unknown."]
11927 pub angular_velocity_z: f32,
11928 #[doc = "Failure flags (0 for no failure)"]
11929 pub failure_flags: GimbalDeviceErrorFlags,
11930 #[doc = "Current gimbal flags set."]
11931 pub flags: GimbalDeviceFlags,
11932 #[doc = "System ID"]
11933 pub target_system: u8,
11934 #[doc = "Component ID"]
11935 pub target_component: u8,
11936 #[doc = "Yaw angle relating the quaternions in earth and body frames (see message description). NaN if unknown."]
11937 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
11938 pub delta_yaw: f32,
11939 #[doc = "Yaw angular velocity relating the angular velocities in earth and body frames (see message description). NaN if unknown."]
11940 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
11941 pub delta_yaw_velocity: f32,
11942 #[doc = "This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set a number between 1-6. If the component ID is separate, this field is not required and must be set to 0."]
11943 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
11944 pub gimbal_device_id: u8,
11945}
11946impl GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
11947 pub const ENCODED_LEN: usize = 49usize;
11948 pub const DEFAULT: Self = Self {
11949 time_boot_ms: 0_u32,
11950 q: [0.0_f32; 4usize],
11951 angular_velocity_x: 0.0_f32,
11952 angular_velocity_y: 0.0_f32,
11953 angular_velocity_z: 0.0_f32,
11954 failure_flags: GimbalDeviceErrorFlags::DEFAULT,
11955 flags: GimbalDeviceFlags::DEFAULT,
11956 target_system: 0_u8,
11957 target_component: 0_u8,
11958 delta_yaw: 0.0_f32,
11959 delta_yaw_velocity: 0.0_f32,
11960 gimbal_device_id: 0_u8,
11961 };
11962 #[cfg(feature = "arbitrary")]
11963 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11964 use arbitrary::{Arbitrary, Unstructured};
11965 let mut buf = [0u8; 1024];
11966 rng.fill_bytes(&mut buf);
11967 let mut unstructured = Unstructured::new(&buf);
11968 Self::arbitrary(&mut unstructured).unwrap_or_default()
11969 }
11970}
11971impl Default for GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
11972 fn default() -> Self {
11973 Self::DEFAULT.clone()
11974 }
11975}
11976impl MessageData for GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
11977 type Message = MavMessage;
11978 const ID: u32 = 285u32;
11979 const NAME: &'static str = "GIMBAL_DEVICE_ATTITUDE_STATUS";
11980 const EXTRA_CRC: u8 = 137u8;
11981 const ENCODED_LEN: usize = 49usize;
11982 fn deser(
11983 _version: MavlinkVersion,
11984 __input: &[u8],
11985 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11986 let avail_len = __input.len();
11987 let mut payload_buf = [0; Self::ENCODED_LEN];
11988 let mut buf = if avail_len < Self::ENCODED_LEN {
11989 payload_buf[0..avail_len].copy_from_slice(__input);
11990 Bytes::new(&payload_buf)
11991 } else {
11992 Bytes::new(__input)
11993 };
11994 let mut __struct = Self::default();
11995 __struct.time_boot_ms = buf.get_u32_le();
11996 for v in &mut __struct.q {
11997 let val = buf.get_f32_le();
11998 *v = val;
11999 }
12000 __struct.angular_velocity_x = buf.get_f32_le();
12001 __struct.angular_velocity_y = buf.get_f32_le();
12002 __struct.angular_velocity_z = buf.get_f32_le();
12003 let tmp = buf.get_u32_le();
12004 __struct.failure_flags = GimbalDeviceErrorFlags::from_bits(
12005 tmp & GimbalDeviceErrorFlags::all().bits(),
12006 )
12007 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
12008 flag_type: "GimbalDeviceErrorFlags",
12009 value: tmp as u32,
12010 })?;
12011 let tmp = buf.get_u16_le();
12012 __struct.flags = GimbalDeviceFlags::from_bits(tmp & GimbalDeviceFlags::all().bits())
12013 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
12014 flag_type: "GimbalDeviceFlags",
12015 value: tmp as u32,
12016 })?;
12017 __struct.target_system = buf.get_u8();
12018 __struct.target_component = buf.get_u8();
12019 __struct.delta_yaw = buf.get_f32_le();
12020 __struct.delta_yaw_velocity = buf.get_f32_le();
12021 __struct.gimbal_device_id = buf.get_u8();
12022 Ok(__struct)
12023 }
12024 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12025 let mut __tmp = BytesMut::new(bytes);
12026 #[allow(clippy::absurd_extreme_comparisons)]
12027 #[allow(unused_comparisons)]
12028 if __tmp.remaining() < Self::ENCODED_LEN {
12029 panic!(
12030 "buffer is too small (need {} bytes, but got {})",
12031 Self::ENCODED_LEN,
12032 __tmp.remaining(),
12033 )
12034 }
12035 __tmp.put_u32_le(self.time_boot_ms);
12036 for val in &self.q {
12037 __tmp.put_f32_le(*val);
12038 }
12039 __tmp.put_f32_le(self.angular_velocity_x);
12040 __tmp.put_f32_le(self.angular_velocity_y);
12041 __tmp.put_f32_le(self.angular_velocity_z);
12042 __tmp.put_u32_le(self.failure_flags.bits());
12043 __tmp.put_u16_le(self.flags.bits());
12044 __tmp.put_u8(self.target_system);
12045 __tmp.put_u8(self.target_component);
12046 __tmp.put_f32_le(self.delta_yaw);
12047 __tmp.put_f32_le(self.delta_yaw_velocity);
12048 __tmp.put_u8(self.gimbal_device_id);
12049 if matches!(version, MavlinkVersion::V2) {
12050 let len = __tmp.len();
12051 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12052 } else {
12053 __tmp.len()
12054 }
12055 }
12056}
12057#[doc = "id: 283"]
12058#[doc = "Information about a low level gimbal. This message should be requested by the gimbal manager or a ground station using MAV_CMD_REQUEST_MESSAGE. The maximum angles and rates are the limits by hardware. However, the limits by software used are likely different/smaller and dependent on mode/settings/etc.."]
12059#[derive(Debug, Clone, PartialEq)]
12060#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12061#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12062pub struct GIMBAL_DEVICE_INFORMATION_DATA {
12063 #[doc = "UID of gimbal hardware (0 if unknown)."]
12064 pub uid: u64,
12065 #[doc = "Timestamp (time since system boot)."]
12066 pub time_boot_ms: u32,
12067 #[doc = "0xff)."]
12068 pub firmware_version: u32,
12069 #[doc = "0xff)."]
12070 pub hardware_version: u32,
12071 #[doc = "Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown."]
12072 pub roll_min: f32,
12073 #[doc = "Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown."]
12074 pub roll_max: f32,
12075 #[doc = "Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown."]
12076 pub pitch_min: f32,
12077 #[doc = "Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown."]
12078 pub pitch_max: f32,
12079 #[doc = "Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown."]
12080 pub yaw_min: f32,
12081 #[doc = "Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown."]
12082 pub yaw_max: f32,
12083 #[doc = "Bitmap of gimbal capability flags."]
12084 pub cap_flags: GimbalDeviceCapFlags,
12085 #[doc = "Bitmap for use for gimbal-specific capability flags."]
12086 pub custom_cap_flags: u16,
12087 #[doc = "Name of the gimbal vendor."]
12088 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12089 pub vendor_name: [u8; 32],
12090 #[doc = "Name of the gimbal model."]
12091 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12092 pub model_name: [u8; 32],
12093 #[doc = "Custom name of the gimbal given to it by the user."]
12094 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12095 pub custom_name: [u8; 32],
12096 #[doc = "This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0."]
12097 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
12098 pub gimbal_device_id: u8,
12099}
12100impl GIMBAL_DEVICE_INFORMATION_DATA {
12101 pub const ENCODED_LEN: usize = 145usize;
12102 pub const DEFAULT: Self = Self {
12103 uid: 0_u64,
12104 time_boot_ms: 0_u32,
12105 firmware_version: 0_u32,
12106 hardware_version: 0_u32,
12107 roll_min: 0.0_f32,
12108 roll_max: 0.0_f32,
12109 pitch_min: 0.0_f32,
12110 pitch_max: 0.0_f32,
12111 yaw_min: 0.0_f32,
12112 yaw_max: 0.0_f32,
12113 cap_flags: GimbalDeviceCapFlags::DEFAULT,
12114 custom_cap_flags: 0_u16,
12115 vendor_name: [0_u8; 32usize],
12116 model_name: [0_u8; 32usize],
12117 custom_name: [0_u8; 32usize],
12118 gimbal_device_id: 0_u8,
12119 };
12120 #[cfg(feature = "arbitrary")]
12121 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12122 use arbitrary::{Arbitrary, Unstructured};
12123 let mut buf = [0u8; 1024];
12124 rng.fill_bytes(&mut buf);
12125 let mut unstructured = Unstructured::new(&buf);
12126 Self::arbitrary(&mut unstructured).unwrap_or_default()
12127 }
12128}
12129impl Default for GIMBAL_DEVICE_INFORMATION_DATA {
12130 fn default() -> Self {
12131 Self::DEFAULT.clone()
12132 }
12133}
12134impl MessageData for GIMBAL_DEVICE_INFORMATION_DATA {
12135 type Message = MavMessage;
12136 const ID: u32 = 283u32;
12137 const NAME: &'static str = "GIMBAL_DEVICE_INFORMATION";
12138 const EXTRA_CRC: u8 = 74u8;
12139 const ENCODED_LEN: usize = 145usize;
12140 fn deser(
12141 _version: MavlinkVersion,
12142 __input: &[u8],
12143 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12144 let avail_len = __input.len();
12145 let mut payload_buf = [0; Self::ENCODED_LEN];
12146 let mut buf = if avail_len < Self::ENCODED_LEN {
12147 payload_buf[0..avail_len].copy_from_slice(__input);
12148 Bytes::new(&payload_buf)
12149 } else {
12150 Bytes::new(__input)
12151 };
12152 let mut __struct = Self::default();
12153 __struct.uid = buf.get_u64_le();
12154 __struct.time_boot_ms = buf.get_u32_le();
12155 __struct.firmware_version = buf.get_u32_le();
12156 __struct.hardware_version = buf.get_u32_le();
12157 __struct.roll_min = buf.get_f32_le();
12158 __struct.roll_max = buf.get_f32_le();
12159 __struct.pitch_min = buf.get_f32_le();
12160 __struct.pitch_max = buf.get_f32_le();
12161 __struct.yaw_min = buf.get_f32_le();
12162 __struct.yaw_max = buf.get_f32_le();
12163 let tmp = buf.get_u16_le();
12164 __struct.cap_flags = GimbalDeviceCapFlags::from_bits(
12165 tmp & GimbalDeviceCapFlags::all().bits(),
12166 )
12167 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
12168 flag_type: "GimbalDeviceCapFlags",
12169 value: tmp as u32,
12170 })?;
12171 __struct.custom_cap_flags = buf.get_u16_le();
12172 for v in &mut __struct.vendor_name {
12173 let val = buf.get_u8();
12174 *v = val;
12175 }
12176 for v in &mut __struct.model_name {
12177 let val = buf.get_u8();
12178 *v = val;
12179 }
12180 for v in &mut __struct.custom_name {
12181 let val = buf.get_u8();
12182 *v = val;
12183 }
12184 __struct.gimbal_device_id = buf.get_u8();
12185 Ok(__struct)
12186 }
12187 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12188 let mut __tmp = BytesMut::new(bytes);
12189 #[allow(clippy::absurd_extreme_comparisons)]
12190 #[allow(unused_comparisons)]
12191 if __tmp.remaining() < Self::ENCODED_LEN {
12192 panic!(
12193 "buffer is too small (need {} bytes, but got {})",
12194 Self::ENCODED_LEN,
12195 __tmp.remaining(),
12196 )
12197 }
12198 __tmp.put_u64_le(self.uid);
12199 __tmp.put_u32_le(self.time_boot_ms);
12200 __tmp.put_u32_le(self.firmware_version);
12201 __tmp.put_u32_le(self.hardware_version);
12202 __tmp.put_f32_le(self.roll_min);
12203 __tmp.put_f32_le(self.roll_max);
12204 __tmp.put_f32_le(self.pitch_min);
12205 __tmp.put_f32_le(self.pitch_max);
12206 __tmp.put_f32_le(self.yaw_min);
12207 __tmp.put_f32_le(self.yaw_max);
12208 __tmp.put_u16_le(self.cap_flags.bits());
12209 __tmp.put_u16_le(self.custom_cap_flags);
12210 for val in &self.vendor_name {
12211 __tmp.put_u8(*val);
12212 }
12213 for val in &self.model_name {
12214 __tmp.put_u8(*val);
12215 }
12216 for val in &self.custom_name {
12217 __tmp.put_u8(*val);
12218 }
12219 __tmp.put_u8(self.gimbal_device_id);
12220 if matches!(version, MavlinkVersion::V2) {
12221 let len = __tmp.len();
12222 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12223 } else {
12224 __tmp.len()
12225 }
12226 }
12227}
12228#[doc = "id: 284"]
12229#[doc = "Low level message to control a gimbal device's attitude. \t This message is to be sent from the gimbal manager to the gimbal device component. \t The quaternion and angular velocities can be set to NaN according to use case. \t For the angles encoded in the quaternion and the angular velocities holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). \t If neither of these flags are set, then (for backwards compatibility) it holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), \t else they are relative to the vehicle heading (vehicle frame). \t Setting both GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME and GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is not allowed. \t These rules are to ensure backwards compatibility. \t New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME."]
12230#[derive(Debug, Clone, PartialEq)]
12231#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12232#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12233pub struct GIMBAL_DEVICE_SET_ATTITUDE_DATA {
12234 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. Set fields to NaN to be ignored."]
12235 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12236 pub q: [f32; 4],
12237 #[doc = "X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN to be ignored."]
12238 pub angular_velocity_x: f32,
12239 #[doc = "Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN to be ignored."]
12240 pub angular_velocity_y: f32,
12241 #[doc = "Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN to be ignored."]
12242 pub angular_velocity_z: f32,
12243 #[doc = "Low level gimbal flags."]
12244 pub flags: GimbalDeviceFlags,
12245 #[doc = "System ID"]
12246 pub target_system: u8,
12247 #[doc = "Component ID"]
12248 pub target_component: u8,
12249}
12250impl GIMBAL_DEVICE_SET_ATTITUDE_DATA {
12251 pub const ENCODED_LEN: usize = 32usize;
12252 pub const DEFAULT: Self = Self {
12253 q: [0.0_f32; 4usize],
12254 angular_velocity_x: 0.0_f32,
12255 angular_velocity_y: 0.0_f32,
12256 angular_velocity_z: 0.0_f32,
12257 flags: GimbalDeviceFlags::DEFAULT,
12258 target_system: 0_u8,
12259 target_component: 0_u8,
12260 };
12261 #[cfg(feature = "arbitrary")]
12262 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12263 use arbitrary::{Arbitrary, Unstructured};
12264 let mut buf = [0u8; 1024];
12265 rng.fill_bytes(&mut buf);
12266 let mut unstructured = Unstructured::new(&buf);
12267 Self::arbitrary(&mut unstructured).unwrap_or_default()
12268 }
12269}
12270impl Default for GIMBAL_DEVICE_SET_ATTITUDE_DATA {
12271 fn default() -> Self {
12272 Self::DEFAULT.clone()
12273 }
12274}
12275impl MessageData for GIMBAL_DEVICE_SET_ATTITUDE_DATA {
12276 type Message = MavMessage;
12277 const ID: u32 = 284u32;
12278 const NAME: &'static str = "GIMBAL_DEVICE_SET_ATTITUDE";
12279 const EXTRA_CRC: u8 = 99u8;
12280 const ENCODED_LEN: usize = 32usize;
12281 fn deser(
12282 _version: MavlinkVersion,
12283 __input: &[u8],
12284 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12285 let avail_len = __input.len();
12286 let mut payload_buf = [0; Self::ENCODED_LEN];
12287 let mut buf = if avail_len < Self::ENCODED_LEN {
12288 payload_buf[0..avail_len].copy_from_slice(__input);
12289 Bytes::new(&payload_buf)
12290 } else {
12291 Bytes::new(__input)
12292 };
12293 let mut __struct = Self::default();
12294 for v in &mut __struct.q {
12295 let val = buf.get_f32_le();
12296 *v = val;
12297 }
12298 __struct.angular_velocity_x = buf.get_f32_le();
12299 __struct.angular_velocity_y = buf.get_f32_le();
12300 __struct.angular_velocity_z = buf.get_f32_le();
12301 let tmp = buf.get_u16_le();
12302 __struct.flags = GimbalDeviceFlags::from_bits(tmp & GimbalDeviceFlags::all().bits())
12303 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
12304 flag_type: "GimbalDeviceFlags",
12305 value: tmp as u32,
12306 })?;
12307 __struct.target_system = buf.get_u8();
12308 __struct.target_component = buf.get_u8();
12309 Ok(__struct)
12310 }
12311 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12312 let mut __tmp = BytesMut::new(bytes);
12313 #[allow(clippy::absurd_extreme_comparisons)]
12314 #[allow(unused_comparisons)]
12315 if __tmp.remaining() < Self::ENCODED_LEN {
12316 panic!(
12317 "buffer is too small (need {} bytes, but got {})",
12318 Self::ENCODED_LEN,
12319 __tmp.remaining(),
12320 )
12321 }
12322 for val in &self.q {
12323 __tmp.put_f32_le(*val);
12324 }
12325 __tmp.put_f32_le(self.angular_velocity_x);
12326 __tmp.put_f32_le(self.angular_velocity_y);
12327 __tmp.put_f32_le(self.angular_velocity_z);
12328 __tmp.put_u16_le(self.flags.bits());
12329 __tmp.put_u8(self.target_system);
12330 __tmp.put_u8(self.target_component);
12331 if matches!(version, MavlinkVersion::V2) {
12332 let len = __tmp.len();
12333 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12334 } else {
12335 __tmp.len()
12336 }
12337 }
12338}
12339#[doc = "id: 280"]
12340#[doc = "Information about a high level gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE."]
12341#[derive(Debug, Clone, PartialEq)]
12342#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12343#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12344pub struct GIMBAL_MANAGER_INFORMATION_DATA {
12345 #[doc = "Timestamp (time since system boot)."]
12346 pub time_boot_ms: u32,
12347 #[doc = "Bitmap of gimbal capability flags."]
12348 pub cap_flags: GimbalManagerCapFlags,
12349 #[doc = "Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)"]
12350 pub roll_min: f32,
12351 #[doc = "Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)"]
12352 pub roll_max: f32,
12353 #[doc = "Minimum pitch angle (positive: up, negative: down)"]
12354 pub pitch_min: f32,
12355 #[doc = "Maximum pitch angle (positive: up, negative: down)"]
12356 pub pitch_max: f32,
12357 #[doc = "Minimum yaw angle (positive: to the right, negative: to the left)"]
12358 pub yaw_min: f32,
12359 #[doc = "Maximum yaw angle (positive: to the right, negative: to the left)"]
12360 pub yaw_max: f32,
12361 #[doc = "Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal)."]
12362 pub gimbal_device_id: u8,
12363}
12364impl GIMBAL_MANAGER_INFORMATION_DATA {
12365 pub const ENCODED_LEN: usize = 33usize;
12366 pub const DEFAULT: Self = Self {
12367 time_boot_ms: 0_u32,
12368 cap_flags: GimbalManagerCapFlags::DEFAULT,
12369 roll_min: 0.0_f32,
12370 roll_max: 0.0_f32,
12371 pitch_min: 0.0_f32,
12372 pitch_max: 0.0_f32,
12373 yaw_min: 0.0_f32,
12374 yaw_max: 0.0_f32,
12375 gimbal_device_id: 0_u8,
12376 };
12377 #[cfg(feature = "arbitrary")]
12378 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12379 use arbitrary::{Arbitrary, Unstructured};
12380 let mut buf = [0u8; 1024];
12381 rng.fill_bytes(&mut buf);
12382 let mut unstructured = Unstructured::new(&buf);
12383 Self::arbitrary(&mut unstructured).unwrap_or_default()
12384 }
12385}
12386impl Default for GIMBAL_MANAGER_INFORMATION_DATA {
12387 fn default() -> Self {
12388 Self::DEFAULT.clone()
12389 }
12390}
12391impl MessageData for GIMBAL_MANAGER_INFORMATION_DATA {
12392 type Message = MavMessage;
12393 const ID: u32 = 280u32;
12394 const NAME: &'static str = "GIMBAL_MANAGER_INFORMATION";
12395 const EXTRA_CRC: u8 = 70u8;
12396 const ENCODED_LEN: usize = 33usize;
12397 fn deser(
12398 _version: MavlinkVersion,
12399 __input: &[u8],
12400 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12401 let avail_len = __input.len();
12402 let mut payload_buf = [0; Self::ENCODED_LEN];
12403 let mut buf = if avail_len < Self::ENCODED_LEN {
12404 payload_buf[0..avail_len].copy_from_slice(__input);
12405 Bytes::new(&payload_buf)
12406 } else {
12407 Bytes::new(__input)
12408 };
12409 let mut __struct = Self::default();
12410 __struct.time_boot_ms = buf.get_u32_le();
12411 let tmp = buf.get_u32_le();
12412 __struct.cap_flags = GimbalManagerCapFlags::from_bits(
12413 tmp & GimbalManagerCapFlags::all().bits(),
12414 )
12415 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
12416 flag_type: "GimbalManagerCapFlags",
12417 value: tmp as u32,
12418 })?;
12419 __struct.roll_min = buf.get_f32_le();
12420 __struct.roll_max = buf.get_f32_le();
12421 __struct.pitch_min = buf.get_f32_le();
12422 __struct.pitch_max = buf.get_f32_le();
12423 __struct.yaw_min = buf.get_f32_le();
12424 __struct.yaw_max = buf.get_f32_le();
12425 __struct.gimbal_device_id = buf.get_u8();
12426 Ok(__struct)
12427 }
12428 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12429 let mut __tmp = BytesMut::new(bytes);
12430 #[allow(clippy::absurd_extreme_comparisons)]
12431 #[allow(unused_comparisons)]
12432 if __tmp.remaining() < Self::ENCODED_LEN {
12433 panic!(
12434 "buffer is too small (need {} bytes, but got {})",
12435 Self::ENCODED_LEN,
12436 __tmp.remaining(),
12437 )
12438 }
12439 __tmp.put_u32_le(self.time_boot_ms);
12440 __tmp.put_u32_le(self.cap_flags.bits());
12441 __tmp.put_f32_le(self.roll_min);
12442 __tmp.put_f32_le(self.roll_max);
12443 __tmp.put_f32_le(self.pitch_min);
12444 __tmp.put_f32_le(self.pitch_max);
12445 __tmp.put_f32_le(self.yaw_min);
12446 __tmp.put_f32_le(self.yaw_max);
12447 __tmp.put_u8(self.gimbal_device_id);
12448 if matches!(version, MavlinkVersion::V2) {
12449 let len = __tmp.len();
12450 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12451 } else {
12452 __tmp.len()
12453 }
12454 }
12455}
12456#[doc = "id: 282"]
12457#[doc = "High level message to control a gimbal's attitude. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case."]
12458#[derive(Debug, Clone, PartialEq)]
12459#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12460#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12461pub struct GIMBAL_MANAGER_SET_ATTITUDE_DATA {
12462 #[doc = "High level gimbal manager flags to use."]
12463 pub flags: GimbalManagerFlags,
12464 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)"]
12465 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12466 pub q: [f32; 4],
12467 #[doc = "X component of angular velocity, positive is rolling to the right, NaN to be ignored."]
12468 pub angular_velocity_x: f32,
12469 #[doc = "Y component of angular velocity, positive is pitching up, NaN to be ignored."]
12470 pub angular_velocity_y: f32,
12471 #[doc = "Z component of angular velocity, positive is yawing to the right, NaN to be ignored."]
12472 pub angular_velocity_z: f32,
12473 #[doc = "System ID"]
12474 pub target_system: u8,
12475 #[doc = "Component ID"]
12476 pub target_component: u8,
12477 #[doc = "Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals)."]
12478 pub gimbal_device_id: u8,
12479}
12480impl GIMBAL_MANAGER_SET_ATTITUDE_DATA {
12481 pub const ENCODED_LEN: usize = 35usize;
12482 pub const DEFAULT: Self = Self {
12483 flags: GimbalManagerFlags::DEFAULT,
12484 q: [0.0_f32; 4usize],
12485 angular_velocity_x: 0.0_f32,
12486 angular_velocity_y: 0.0_f32,
12487 angular_velocity_z: 0.0_f32,
12488 target_system: 0_u8,
12489 target_component: 0_u8,
12490 gimbal_device_id: 0_u8,
12491 };
12492 #[cfg(feature = "arbitrary")]
12493 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12494 use arbitrary::{Arbitrary, Unstructured};
12495 let mut buf = [0u8; 1024];
12496 rng.fill_bytes(&mut buf);
12497 let mut unstructured = Unstructured::new(&buf);
12498 Self::arbitrary(&mut unstructured).unwrap_or_default()
12499 }
12500}
12501impl Default for GIMBAL_MANAGER_SET_ATTITUDE_DATA {
12502 fn default() -> Self {
12503 Self::DEFAULT.clone()
12504 }
12505}
12506impl MessageData for GIMBAL_MANAGER_SET_ATTITUDE_DATA {
12507 type Message = MavMessage;
12508 const ID: u32 = 282u32;
12509 const NAME: &'static str = "GIMBAL_MANAGER_SET_ATTITUDE";
12510 const EXTRA_CRC: u8 = 123u8;
12511 const ENCODED_LEN: usize = 35usize;
12512 fn deser(
12513 _version: MavlinkVersion,
12514 __input: &[u8],
12515 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12516 let avail_len = __input.len();
12517 let mut payload_buf = [0; Self::ENCODED_LEN];
12518 let mut buf = if avail_len < Self::ENCODED_LEN {
12519 payload_buf[0..avail_len].copy_from_slice(__input);
12520 Bytes::new(&payload_buf)
12521 } else {
12522 Bytes::new(__input)
12523 };
12524 let mut __struct = Self::default();
12525 let tmp = buf.get_u32_le();
12526 __struct.flags = GimbalManagerFlags::from_bits(tmp & GimbalManagerFlags::all().bits())
12527 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
12528 flag_type: "GimbalManagerFlags",
12529 value: tmp as u32,
12530 })?;
12531 for v in &mut __struct.q {
12532 let val = buf.get_f32_le();
12533 *v = val;
12534 }
12535 __struct.angular_velocity_x = buf.get_f32_le();
12536 __struct.angular_velocity_y = buf.get_f32_le();
12537 __struct.angular_velocity_z = buf.get_f32_le();
12538 __struct.target_system = buf.get_u8();
12539 __struct.target_component = buf.get_u8();
12540 __struct.gimbal_device_id = buf.get_u8();
12541 Ok(__struct)
12542 }
12543 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12544 let mut __tmp = BytesMut::new(bytes);
12545 #[allow(clippy::absurd_extreme_comparisons)]
12546 #[allow(unused_comparisons)]
12547 if __tmp.remaining() < Self::ENCODED_LEN {
12548 panic!(
12549 "buffer is too small (need {} bytes, but got {})",
12550 Self::ENCODED_LEN,
12551 __tmp.remaining(),
12552 )
12553 }
12554 __tmp.put_u32_le(self.flags.bits());
12555 for val in &self.q {
12556 __tmp.put_f32_le(*val);
12557 }
12558 __tmp.put_f32_le(self.angular_velocity_x);
12559 __tmp.put_f32_le(self.angular_velocity_y);
12560 __tmp.put_f32_le(self.angular_velocity_z);
12561 __tmp.put_u8(self.target_system);
12562 __tmp.put_u8(self.target_component);
12563 __tmp.put_u8(self.gimbal_device_id);
12564 if matches!(version, MavlinkVersion::V2) {
12565 let len = __tmp.len();
12566 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12567 } else {
12568 __tmp.len()
12569 }
12570 }
12571}
12572#[doc = "id: 288"]
12573#[doc = "High level message to control a gimbal manually. The angles or angular rates are unitless; the actual rates will depend on internal gimbal manager settings/configuration (e.g. set by parameters). This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case."]
12574#[derive(Debug, Clone, PartialEq)]
12575#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12576#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12577pub struct GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
12578 #[doc = "High level gimbal manager flags."]
12579 pub flags: GimbalManagerFlags,
12580 #[doc = "Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored)."]
12581 pub pitch: f32,
12582 #[doc = "Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored)."]
12583 pub yaw: f32,
12584 #[doc = "Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored)."]
12585 pub pitch_rate: f32,
12586 #[doc = "Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored)."]
12587 pub yaw_rate: f32,
12588 #[doc = "System ID"]
12589 pub target_system: u8,
12590 #[doc = "Component ID"]
12591 pub target_component: u8,
12592 #[doc = "Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals)."]
12593 pub gimbal_device_id: u8,
12594}
12595impl GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
12596 pub const ENCODED_LEN: usize = 23usize;
12597 pub const DEFAULT: Self = Self {
12598 flags: GimbalManagerFlags::DEFAULT,
12599 pitch: 0.0_f32,
12600 yaw: 0.0_f32,
12601 pitch_rate: 0.0_f32,
12602 yaw_rate: 0.0_f32,
12603 target_system: 0_u8,
12604 target_component: 0_u8,
12605 gimbal_device_id: 0_u8,
12606 };
12607 #[cfg(feature = "arbitrary")]
12608 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12609 use arbitrary::{Arbitrary, Unstructured};
12610 let mut buf = [0u8; 1024];
12611 rng.fill_bytes(&mut buf);
12612 let mut unstructured = Unstructured::new(&buf);
12613 Self::arbitrary(&mut unstructured).unwrap_or_default()
12614 }
12615}
12616impl Default for GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
12617 fn default() -> Self {
12618 Self::DEFAULT.clone()
12619 }
12620}
12621impl MessageData for GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
12622 type Message = MavMessage;
12623 const ID: u32 = 288u32;
12624 const NAME: &'static str = "GIMBAL_MANAGER_SET_MANUAL_CONTROL";
12625 const EXTRA_CRC: u8 = 20u8;
12626 const ENCODED_LEN: usize = 23usize;
12627 fn deser(
12628 _version: MavlinkVersion,
12629 __input: &[u8],
12630 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12631 let avail_len = __input.len();
12632 let mut payload_buf = [0; Self::ENCODED_LEN];
12633 let mut buf = if avail_len < Self::ENCODED_LEN {
12634 payload_buf[0..avail_len].copy_from_slice(__input);
12635 Bytes::new(&payload_buf)
12636 } else {
12637 Bytes::new(__input)
12638 };
12639 let mut __struct = Self::default();
12640 let tmp = buf.get_u32_le();
12641 __struct.flags = GimbalManagerFlags::from_bits(tmp & GimbalManagerFlags::all().bits())
12642 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
12643 flag_type: "GimbalManagerFlags",
12644 value: tmp as u32,
12645 })?;
12646 __struct.pitch = buf.get_f32_le();
12647 __struct.yaw = buf.get_f32_le();
12648 __struct.pitch_rate = buf.get_f32_le();
12649 __struct.yaw_rate = buf.get_f32_le();
12650 __struct.target_system = buf.get_u8();
12651 __struct.target_component = buf.get_u8();
12652 __struct.gimbal_device_id = buf.get_u8();
12653 Ok(__struct)
12654 }
12655 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12656 let mut __tmp = BytesMut::new(bytes);
12657 #[allow(clippy::absurd_extreme_comparisons)]
12658 #[allow(unused_comparisons)]
12659 if __tmp.remaining() < Self::ENCODED_LEN {
12660 panic!(
12661 "buffer is too small (need {} bytes, but got {})",
12662 Self::ENCODED_LEN,
12663 __tmp.remaining(),
12664 )
12665 }
12666 __tmp.put_u32_le(self.flags.bits());
12667 __tmp.put_f32_le(self.pitch);
12668 __tmp.put_f32_le(self.yaw);
12669 __tmp.put_f32_le(self.pitch_rate);
12670 __tmp.put_f32_le(self.yaw_rate);
12671 __tmp.put_u8(self.target_system);
12672 __tmp.put_u8(self.target_component);
12673 __tmp.put_u8(self.gimbal_device_id);
12674 if matches!(version, MavlinkVersion::V2) {
12675 let len = __tmp.len();
12676 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12677 } else {
12678 __tmp.len()
12679 }
12680 }
12681}
12682#[doc = "id: 287"]
12683#[doc = "Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation."]
12684#[derive(Debug, Clone, PartialEq)]
12685#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12686#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12687pub struct GIMBAL_MANAGER_SET_PITCHYAW_DATA {
12688 #[doc = "High level gimbal manager flags to use."]
12689 pub flags: GimbalManagerFlags,
12690 #[doc = "Pitch angle (positive: up, negative: down, NaN to be ignored)."]
12691 pub pitch: f32,
12692 #[doc = "Yaw angle (positive: to the right, negative: to the left, NaN to be ignored)."]
12693 pub yaw: f32,
12694 #[doc = "Pitch angular rate (positive: up, negative: down, NaN to be ignored)."]
12695 pub pitch_rate: f32,
12696 #[doc = "Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored)."]
12697 pub yaw_rate: f32,
12698 #[doc = "System ID"]
12699 pub target_system: u8,
12700 #[doc = "Component ID"]
12701 pub target_component: u8,
12702 #[doc = "Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals)."]
12703 pub gimbal_device_id: u8,
12704}
12705impl GIMBAL_MANAGER_SET_PITCHYAW_DATA {
12706 pub const ENCODED_LEN: usize = 23usize;
12707 pub const DEFAULT: Self = Self {
12708 flags: GimbalManagerFlags::DEFAULT,
12709 pitch: 0.0_f32,
12710 yaw: 0.0_f32,
12711 pitch_rate: 0.0_f32,
12712 yaw_rate: 0.0_f32,
12713 target_system: 0_u8,
12714 target_component: 0_u8,
12715 gimbal_device_id: 0_u8,
12716 };
12717 #[cfg(feature = "arbitrary")]
12718 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12719 use arbitrary::{Arbitrary, Unstructured};
12720 let mut buf = [0u8; 1024];
12721 rng.fill_bytes(&mut buf);
12722 let mut unstructured = Unstructured::new(&buf);
12723 Self::arbitrary(&mut unstructured).unwrap_or_default()
12724 }
12725}
12726impl Default for GIMBAL_MANAGER_SET_PITCHYAW_DATA {
12727 fn default() -> Self {
12728 Self::DEFAULT.clone()
12729 }
12730}
12731impl MessageData for GIMBAL_MANAGER_SET_PITCHYAW_DATA {
12732 type Message = MavMessage;
12733 const ID: u32 = 287u32;
12734 const NAME: &'static str = "GIMBAL_MANAGER_SET_PITCHYAW";
12735 const EXTRA_CRC: u8 = 1u8;
12736 const ENCODED_LEN: usize = 23usize;
12737 fn deser(
12738 _version: MavlinkVersion,
12739 __input: &[u8],
12740 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12741 let avail_len = __input.len();
12742 let mut payload_buf = [0; Self::ENCODED_LEN];
12743 let mut buf = if avail_len < Self::ENCODED_LEN {
12744 payload_buf[0..avail_len].copy_from_slice(__input);
12745 Bytes::new(&payload_buf)
12746 } else {
12747 Bytes::new(__input)
12748 };
12749 let mut __struct = Self::default();
12750 let tmp = buf.get_u32_le();
12751 __struct.flags = GimbalManagerFlags::from_bits(tmp & GimbalManagerFlags::all().bits())
12752 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
12753 flag_type: "GimbalManagerFlags",
12754 value: tmp as u32,
12755 })?;
12756 __struct.pitch = buf.get_f32_le();
12757 __struct.yaw = buf.get_f32_le();
12758 __struct.pitch_rate = buf.get_f32_le();
12759 __struct.yaw_rate = buf.get_f32_le();
12760 __struct.target_system = buf.get_u8();
12761 __struct.target_component = buf.get_u8();
12762 __struct.gimbal_device_id = buf.get_u8();
12763 Ok(__struct)
12764 }
12765 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12766 let mut __tmp = BytesMut::new(bytes);
12767 #[allow(clippy::absurd_extreme_comparisons)]
12768 #[allow(unused_comparisons)]
12769 if __tmp.remaining() < Self::ENCODED_LEN {
12770 panic!(
12771 "buffer is too small (need {} bytes, but got {})",
12772 Self::ENCODED_LEN,
12773 __tmp.remaining(),
12774 )
12775 }
12776 __tmp.put_u32_le(self.flags.bits());
12777 __tmp.put_f32_le(self.pitch);
12778 __tmp.put_f32_le(self.yaw);
12779 __tmp.put_f32_le(self.pitch_rate);
12780 __tmp.put_f32_le(self.yaw_rate);
12781 __tmp.put_u8(self.target_system);
12782 __tmp.put_u8(self.target_component);
12783 __tmp.put_u8(self.gimbal_device_id);
12784 if matches!(version, MavlinkVersion::V2) {
12785 let len = __tmp.len();
12786 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12787 } else {
12788 __tmp.len()
12789 }
12790 }
12791}
12792#[doc = "id: 281"]
12793#[doc = "Current status about a high level gimbal manager. This message should be broadcast at a low regular rate (e.g. 5Hz)."]
12794#[derive(Debug, Clone, PartialEq)]
12795#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12796#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12797pub struct GIMBAL_MANAGER_STATUS_DATA {
12798 #[doc = "Timestamp (time since system boot)."]
12799 pub time_boot_ms: u32,
12800 #[doc = "High level gimbal manager flags currently applied."]
12801 pub flags: GimbalManagerFlags,
12802 #[doc = "Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal)."]
12803 pub gimbal_device_id: u8,
12804 #[doc = "System ID of MAVLink component with primary control, 0 for none."]
12805 pub primary_control_sysid: u8,
12806 #[doc = "Component ID of MAVLink component with primary control, 0 for none."]
12807 pub primary_control_compid: u8,
12808 #[doc = "System ID of MAVLink component with secondary control, 0 for none."]
12809 pub secondary_control_sysid: u8,
12810 #[doc = "Component ID of MAVLink component with secondary control, 0 for none."]
12811 pub secondary_control_compid: u8,
12812}
12813impl GIMBAL_MANAGER_STATUS_DATA {
12814 pub const ENCODED_LEN: usize = 13usize;
12815 pub const DEFAULT: Self = Self {
12816 time_boot_ms: 0_u32,
12817 flags: GimbalManagerFlags::DEFAULT,
12818 gimbal_device_id: 0_u8,
12819 primary_control_sysid: 0_u8,
12820 primary_control_compid: 0_u8,
12821 secondary_control_sysid: 0_u8,
12822 secondary_control_compid: 0_u8,
12823 };
12824 #[cfg(feature = "arbitrary")]
12825 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12826 use arbitrary::{Arbitrary, Unstructured};
12827 let mut buf = [0u8; 1024];
12828 rng.fill_bytes(&mut buf);
12829 let mut unstructured = Unstructured::new(&buf);
12830 Self::arbitrary(&mut unstructured).unwrap_or_default()
12831 }
12832}
12833impl Default for GIMBAL_MANAGER_STATUS_DATA {
12834 fn default() -> Self {
12835 Self::DEFAULT.clone()
12836 }
12837}
12838impl MessageData for GIMBAL_MANAGER_STATUS_DATA {
12839 type Message = MavMessage;
12840 const ID: u32 = 281u32;
12841 const NAME: &'static str = "GIMBAL_MANAGER_STATUS";
12842 const EXTRA_CRC: u8 = 48u8;
12843 const ENCODED_LEN: usize = 13usize;
12844 fn deser(
12845 _version: MavlinkVersion,
12846 __input: &[u8],
12847 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12848 let avail_len = __input.len();
12849 let mut payload_buf = [0; Self::ENCODED_LEN];
12850 let mut buf = if avail_len < Self::ENCODED_LEN {
12851 payload_buf[0..avail_len].copy_from_slice(__input);
12852 Bytes::new(&payload_buf)
12853 } else {
12854 Bytes::new(__input)
12855 };
12856 let mut __struct = Self::default();
12857 __struct.time_boot_ms = buf.get_u32_le();
12858 let tmp = buf.get_u32_le();
12859 __struct.flags = GimbalManagerFlags::from_bits(tmp & GimbalManagerFlags::all().bits())
12860 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
12861 flag_type: "GimbalManagerFlags",
12862 value: tmp as u32,
12863 })?;
12864 __struct.gimbal_device_id = buf.get_u8();
12865 __struct.primary_control_sysid = buf.get_u8();
12866 __struct.primary_control_compid = buf.get_u8();
12867 __struct.secondary_control_sysid = buf.get_u8();
12868 __struct.secondary_control_compid = buf.get_u8();
12869 Ok(__struct)
12870 }
12871 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12872 let mut __tmp = BytesMut::new(bytes);
12873 #[allow(clippy::absurd_extreme_comparisons)]
12874 #[allow(unused_comparisons)]
12875 if __tmp.remaining() < Self::ENCODED_LEN {
12876 panic!(
12877 "buffer is too small (need {} bytes, but got {})",
12878 Self::ENCODED_LEN,
12879 __tmp.remaining(),
12880 )
12881 }
12882 __tmp.put_u32_le(self.time_boot_ms);
12883 __tmp.put_u32_le(self.flags.bits());
12884 __tmp.put_u8(self.gimbal_device_id);
12885 __tmp.put_u8(self.primary_control_sysid);
12886 __tmp.put_u8(self.primary_control_compid);
12887 __tmp.put_u8(self.secondary_control_sysid);
12888 __tmp.put_u8(self.secondary_control_compid);
12889 if matches!(version, MavlinkVersion::V2) {
12890 let len = __tmp.len();
12891 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12892 } else {
12893 __tmp.len()
12894 }
12895 }
12896}
12897#[doc = "id: 33"]
12898#[doc = "The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient."]
12899#[derive(Debug, Clone, PartialEq)]
12900#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12901#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12902pub struct GLOBAL_POSITION_INT_DATA {
12903 #[doc = "Timestamp (time since system boot)."]
12904 pub time_boot_ms: u32,
12905 #[doc = "Latitude, expressed"]
12906 pub lat: i32,
12907 #[doc = "Longitude, expressed"]
12908 pub lon: i32,
12909 #[doc = "Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL."]
12910 pub alt: i32,
12911 #[doc = "Altitude above home"]
12912 pub relative_alt: i32,
12913 #[doc = "Ground X Speed (Latitude, positive north)"]
12914 pub vx: i16,
12915 #[doc = "Ground Y Speed (Longitude, positive east)"]
12916 pub vy: i16,
12917 #[doc = "Ground Z Speed (Altitude, positive down)"]
12918 pub vz: i16,
12919 #[doc = "Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
12920 pub hdg: u16,
12921}
12922impl GLOBAL_POSITION_INT_DATA {
12923 pub const ENCODED_LEN: usize = 28usize;
12924 pub const DEFAULT: Self = Self {
12925 time_boot_ms: 0_u32,
12926 lat: 0_i32,
12927 lon: 0_i32,
12928 alt: 0_i32,
12929 relative_alt: 0_i32,
12930 vx: 0_i16,
12931 vy: 0_i16,
12932 vz: 0_i16,
12933 hdg: 0_u16,
12934 };
12935 #[cfg(feature = "arbitrary")]
12936 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12937 use arbitrary::{Arbitrary, Unstructured};
12938 let mut buf = [0u8; 1024];
12939 rng.fill_bytes(&mut buf);
12940 let mut unstructured = Unstructured::new(&buf);
12941 Self::arbitrary(&mut unstructured).unwrap_or_default()
12942 }
12943}
12944impl Default for GLOBAL_POSITION_INT_DATA {
12945 fn default() -> Self {
12946 Self::DEFAULT.clone()
12947 }
12948}
12949impl MessageData for GLOBAL_POSITION_INT_DATA {
12950 type Message = MavMessage;
12951 const ID: u32 = 33u32;
12952 const NAME: &'static str = "GLOBAL_POSITION_INT";
12953 const EXTRA_CRC: u8 = 104u8;
12954 const ENCODED_LEN: usize = 28usize;
12955 fn deser(
12956 _version: MavlinkVersion,
12957 __input: &[u8],
12958 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12959 let avail_len = __input.len();
12960 let mut payload_buf = [0; Self::ENCODED_LEN];
12961 let mut buf = if avail_len < Self::ENCODED_LEN {
12962 payload_buf[0..avail_len].copy_from_slice(__input);
12963 Bytes::new(&payload_buf)
12964 } else {
12965 Bytes::new(__input)
12966 };
12967 let mut __struct = Self::default();
12968 __struct.time_boot_ms = buf.get_u32_le();
12969 __struct.lat = buf.get_i32_le();
12970 __struct.lon = buf.get_i32_le();
12971 __struct.alt = buf.get_i32_le();
12972 __struct.relative_alt = buf.get_i32_le();
12973 __struct.vx = buf.get_i16_le();
12974 __struct.vy = buf.get_i16_le();
12975 __struct.vz = buf.get_i16_le();
12976 __struct.hdg = buf.get_u16_le();
12977 Ok(__struct)
12978 }
12979 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12980 let mut __tmp = BytesMut::new(bytes);
12981 #[allow(clippy::absurd_extreme_comparisons)]
12982 #[allow(unused_comparisons)]
12983 if __tmp.remaining() < Self::ENCODED_LEN {
12984 panic!(
12985 "buffer is too small (need {} bytes, but got {})",
12986 Self::ENCODED_LEN,
12987 __tmp.remaining(),
12988 )
12989 }
12990 __tmp.put_u32_le(self.time_boot_ms);
12991 __tmp.put_i32_le(self.lat);
12992 __tmp.put_i32_le(self.lon);
12993 __tmp.put_i32_le(self.alt);
12994 __tmp.put_i32_le(self.relative_alt);
12995 __tmp.put_i16_le(self.vx);
12996 __tmp.put_i16_le(self.vy);
12997 __tmp.put_i16_le(self.vz);
12998 __tmp.put_u16_le(self.hdg);
12999 if matches!(version, MavlinkVersion::V2) {
13000 let len = __tmp.len();
13001 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13002 } else {
13003 __tmp.len()
13004 }
13005 }
13006}
13007#[doc = "id: 63"]
13008#[doc = "The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset."]
13009#[derive(Debug, Clone, PartialEq)]
13010#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13011#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13012pub struct GLOBAL_POSITION_INT_COV_DATA {
13013 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
13014 pub time_usec: u64,
13015 #[doc = "Latitude"]
13016 pub lat: i32,
13017 #[doc = "Longitude"]
13018 pub lon: i32,
13019 #[doc = "Altitude in meters above MSL"]
13020 pub alt: i32,
13021 #[doc = "Altitude above ground"]
13022 pub relative_alt: i32,
13023 #[doc = "Ground X Speed (Latitude)"]
13024 pub vx: f32,
13025 #[doc = "Ground Y Speed (Longitude)"]
13026 pub vy: f32,
13027 #[doc = "Ground Z Speed (Altitude)"]
13028 pub vz: f32,
13029 #[doc = "Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array."]
13030 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13031 pub covariance: [f32; 36],
13032 #[doc = "Class id of the estimator this estimate originated from."]
13033 pub estimator_type: MavEstimatorType,
13034}
13035impl GLOBAL_POSITION_INT_COV_DATA {
13036 pub const ENCODED_LEN: usize = 181usize;
13037 pub const DEFAULT: Self = Self {
13038 time_usec: 0_u64,
13039 lat: 0_i32,
13040 lon: 0_i32,
13041 alt: 0_i32,
13042 relative_alt: 0_i32,
13043 vx: 0.0_f32,
13044 vy: 0.0_f32,
13045 vz: 0.0_f32,
13046 covariance: [0.0_f32; 36usize],
13047 estimator_type: MavEstimatorType::DEFAULT,
13048 };
13049 #[cfg(feature = "arbitrary")]
13050 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13051 use arbitrary::{Arbitrary, Unstructured};
13052 let mut buf = [0u8; 1024];
13053 rng.fill_bytes(&mut buf);
13054 let mut unstructured = Unstructured::new(&buf);
13055 Self::arbitrary(&mut unstructured).unwrap_or_default()
13056 }
13057}
13058impl Default for GLOBAL_POSITION_INT_COV_DATA {
13059 fn default() -> Self {
13060 Self::DEFAULT.clone()
13061 }
13062}
13063impl MessageData for GLOBAL_POSITION_INT_COV_DATA {
13064 type Message = MavMessage;
13065 const ID: u32 = 63u32;
13066 const NAME: &'static str = "GLOBAL_POSITION_INT_COV";
13067 const EXTRA_CRC: u8 = 119u8;
13068 const ENCODED_LEN: usize = 181usize;
13069 fn deser(
13070 _version: MavlinkVersion,
13071 __input: &[u8],
13072 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13073 let avail_len = __input.len();
13074 let mut payload_buf = [0; Self::ENCODED_LEN];
13075 let mut buf = if avail_len < Self::ENCODED_LEN {
13076 payload_buf[0..avail_len].copy_from_slice(__input);
13077 Bytes::new(&payload_buf)
13078 } else {
13079 Bytes::new(__input)
13080 };
13081 let mut __struct = Self::default();
13082 __struct.time_usec = buf.get_u64_le();
13083 __struct.lat = buf.get_i32_le();
13084 __struct.lon = buf.get_i32_le();
13085 __struct.alt = buf.get_i32_le();
13086 __struct.relative_alt = buf.get_i32_le();
13087 __struct.vx = buf.get_f32_le();
13088 __struct.vy = buf.get_f32_le();
13089 __struct.vz = buf.get_f32_le();
13090 for v in &mut __struct.covariance {
13091 let val = buf.get_f32_le();
13092 *v = val;
13093 }
13094 let tmp = buf.get_u8();
13095 __struct.estimator_type =
13096 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13097 enum_type: "MavEstimatorType",
13098 value: tmp as u32,
13099 })?;
13100 Ok(__struct)
13101 }
13102 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13103 let mut __tmp = BytesMut::new(bytes);
13104 #[allow(clippy::absurd_extreme_comparisons)]
13105 #[allow(unused_comparisons)]
13106 if __tmp.remaining() < Self::ENCODED_LEN {
13107 panic!(
13108 "buffer is too small (need {} bytes, but got {})",
13109 Self::ENCODED_LEN,
13110 __tmp.remaining(),
13111 )
13112 }
13113 __tmp.put_u64_le(self.time_usec);
13114 __tmp.put_i32_le(self.lat);
13115 __tmp.put_i32_le(self.lon);
13116 __tmp.put_i32_le(self.alt);
13117 __tmp.put_i32_le(self.relative_alt);
13118 __tmp.put_f32_le(self.vx);
13119 __tmp.put_f32_le(self.vy);
13120 __tmp.put_f32_le(self.vz);
13121 for val in &self.covariance {
13122 __tmp.put_f32_le(*val);
13123 }
13124 __tmp.put_u8(self.estimator_type as u8);
13125 if matches!(version, MavlinkVersion::V2) {
13126 let len = __tmp.len();
13127 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13128 } else {
13129 __tmp.len()
13130 }
13131 }
13132}
13133#[doc = "id: 101"]
13134#[doc = "Global position/attitude estimate from a vision source."]
13135#[derive(Debug, Clone, PartialEq)]
13136#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13137#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13138pub struct GLOBAL_VISION_POSITION_ESTIMATE_DATA {
13139 #[doc = "Timestamp (UNIX time or since system boot)"]
13140 pub usec: u64,
13141 #[doc = "Global X position"]
13142 pub x: f32,
13143 #[doc = "Global Y position"]
13144 pub y: f32,
13145 #[doc = "Global Z position"]
13146 pub z: f32,
13147 #[doc = "Roll angle"]
13148 pub roll: f32,
13149 #[doc = "Pitch angle"]
13150 pub pitch: f32,
13151 #[doc = "Yaw angle"]
13152 pub yaw: f32,
13153 #[doc = "Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
13154 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13155 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13156 pub covariance: [f32; 21],
13157 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
13158 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13159 pub reset_counter: u8,
13160}
13161impl GLOBAL_VISION_POSITION_ESTIMATE_DATA {
13162 pub const ENCODED_LEN: usize = 117usize;
13163 pub const DEFAULT: Self = Self {
13164 usec: 0_u64,
13165 x: 0.0_f32,
13166 y: 0.0_f32,
13167 z: 0.0_f32,
13168 roll: 0.0_f32,
13169 pitch: 0.0_f32,
13170 yaw: 0.0_f32,
13171 covariance: [0.0_f32; 21usize],
13172 reset_counter: 0_u8,
13173 };
13174 #[cfg(feature = "arbitrary")]
13175 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13176 use arbitrary::{Arbitrary, Unstructured};
13177 let mut buf = [0u8; 1024];
13178 rng.fill_bytes(&mut buf);
13179 let mut unstructured = Unstructured::new(&buf);
13180 Self::arbitrary(&mut unstructured).unwrap_or_default()
13181 }
13182}
13183impl Default for GLOBAL_VISION_POSITION_ESTIMATE_DATA {
13184 fn default() -> Self {
13185 Self::DEFAULT.clone()
13186 }
13187}
13188impl MessageData for GLOBAL_VISION_POSITION_ESTIMATE_DATA {
13189 type Message = MavMessage;
13190 const ID: u32 = 101u32;
13191 const NAME: &'static str = "GLOBAL_VISION_POSITION_ESTIMATE";
13192 const EXTRA_CRC: u8 = 102u8;
13193 const ENCODED_LEN: usize = 117usize;
13194 fn deser(
13195 _version: MavlinkVersion,
13196 __input: &[u8],
13197 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13198 let avail_len = __input.len();
13199 let mut payload_buf = [0; Self::ENCODED_LEN];
13200 let mut buf = if avail_len < Self::ENCODED_LEN {
13201 payload_buf[0..avail_len].copy_from_slice(__input);
13202 Bytes::new(&payload_buf)
13203 } else {
13204 Bytes::new(__input)
13205 };
13206 let mut __struct = Self::default();
13207 __struct.usec = buf.get_u64_le();
13208 __struct.x = buf.get_f32_le();
13209 __struct.y = buf.get_f32_le();
13210 __struct.z = buf.get_f32_le();
13211 __struct.roll = buf.get_f32_le();
13212 __struct.pitch = buf.get_f32_le();
13213 __struct.yaw = buf.get_f32_le();
13214 for v in &mut __struct.covariance {
13215 let val = buf.get_f32_le();
13216 *v = val;
13217 }
13218 __struct.reset_counter = buf.get_u8();
13219 Ok(__struct)
13220 }
13221 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13222 let mut __tmp = BytesMut::new(bytes);
13223 #[allow(clippy::absurd_extreme_comparisons)]
13224 #[allow(unused_comparisons)]
13225 if __tmp.remaining() < Self::ENCODED_LEN {
13226 panic!(
13227 "buffer is too small (need {} bytes, but got {})",
13228 Self::ENCODED_LEN,
13229 __tmp.remaining(),
13230 )
13231 }
13232 __tmp.put_u64_le(self.usec);
13233 __tmp.put_f32_le(self.x);
13234 __tmp.put_f32_le(self.y);
13235 __tmp.put_f32_le(self.z);
13236 __tmp.put_f32_le(self.roll);
13237 __tmp.put_f32_le(self.pitch);
13238 __tmp.put_f32_le(self.yaw);
13239 for val in &self.covariance {
13240 __tmp.put_f32_le(*val);
13241 }
13242 __tmp.put_u8(self.reset_counter);
13243 if matches!(version, MavlinkVersion::V2) {
13244 let len = __tmp.len();
13245 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13246 } else {
13247 __tmp.len()
13248 }
13249 }
13250}
13251#[doc = "id: 124"]
13252#[doc = "Second GPS data."]
13253#[derive(Debug, Clone, PartialEq)]
13254#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13255#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13256pub struct GPS2_RAW_DATA {
13257 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
13258 pub time_usec: u64,
13259 #[doc = "Latitude (WGS84)"]
13260 pub lat: i32,
13261 #[doc = "Longitude (WGS84)"]
13262 pub lon: i32,
13263 #[doc = "Altitude (MSL). Positive for up."]
13264 pub alt: i32,
13265 #[doc = "Age of DGPS info"]
13266 pub dgps_age: u32,
13267 #[doc = "GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
13268 pub eph: u16,
13269 #[doc = "GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
13270 pub epv: u16,
13271 #[doc = "GPS ground speed. If unknown, set to: UINT16_MAX"]
13272 pub vel: u16,
13273 #[doc = "Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
13274 pub cog: u16,
13275 #[doc = "GPS fix type."]
13276 pub fix_type: GpsFixType,
13277 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
13278 pub satellites_visible: u8,
13279 #[doc = "Number of DGPS satellites"]
13280 pub dgps_numch: u8,
13281 #[doc = "Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north."]
13282 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13283 pub yaw: u16,
13284 #[doc = "Altitude (above WGS84, EGM96 ellipsoid). Positive for up."]
13285 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13286 pub alt_ellipsoid: i32,
13287 #[doc = "Position uncertainty."]
13288 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13289 pub h_acc: u32,
13290 #[doc = "Altitude uncertainty."]
13291 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13292 pub v_acc: u32,
13293 #[doc = "Speed uncertainty."]
13294 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13295 pub vel_acc: u32,
13296 #[doc = "Heading / track uncertainty"]
13297 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13298 pub hdg_acc: u32,
13299}
13300impl GPS2_RAW_DATA {
13301 pub const ENCODED_LEN: usize = 57usize;
13302 pub const DEFAULT: Self = Self {
13303 time_usec: 0_u64,
13304 lat: 0_i32,
13305 lon: 0_i32,
13306 alt: 0_i32,
13307 dgps_age: 0_u32,
13308 eph: 0_u16,
13309 epv: 0_u16,
13310 vel: 0_u16,
13311 cog: 0_u16,
13312 fix_type: GpsFixType::DEFAULT,
13313 satellites_visible: 0_u8,
13314 dgps_numch: 0_u8,
13315 yaw: 0_u16,
13316 alt_ellipsoid: 0_i32,
13317 h_acc: 0_u32,
13318 v_acc: 0_u32,
13319 vel_acc: 0_u32,
13320 hdg_acc: 0_u32,
13321 };
13322 #[cfg(feature = "arbitrary")]
13323 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13324 use arbitrary::{Arbitrary, Unstructured};
13325 let mut buf = [0u8; 1024];
13326 rng.fill_bytes(&mut buf);
13327 let mut unstructured = Unstructured::new(&buf);
13328 Self::arbitrary(&mut unstructured).unwrap_or_default()
13329 }
13330}
13331impl Default for GPS2_RAW_DATA {
13332 fn default() -> Self {
13333 Self::DEFAULT.clone()
13334 }
13335}
13336impl MessageData for GPS2_RAW_DATA {
13337 type Message = MavMessage;
13338 const ID: u32 = 124u32;
13339 const NAME: &'static str = "GPS2_RAW";
13340 const EXTRA_CRC: u8 = 87u8;
13341 const ENCODED_LEN: usize = 57usize;
13342 fn deser(
13343 _version: MavlinkVersion,
13344 __input: &[u8],
13345 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13346 let avail_len = __input.len();
13347 let mut payload_buf = [0; Self::ENCODED_LEN];
13348 let mut buf = if avail_len < Self::ENCODED_LEN {
13349 payload_buf[0..avail_len].copy_from_slice(__input);
13350 Bytes::new(&payload_buf)
13351 } else {
13352 Bytes::new(__input)
13353 };
13354 let mut __struct = Self::default();
13355 __struct.time_usec = buf.get_u64_le();
13356 __struct.lat = buf.get_i32_le();
13357 __struct.lon = buf.get_i32_le();
13358 __struct.alt = buf.get_i32_le();
13359 __struct.dgps_age = buf.get_u32_le();
13360 __struct.eph = buf.get_u16_le();
13361 __struct.epv = buf.get_u16_le();
13362 __struct.vel = buf.get_u16_le();
13363 __struct.cog = buf.get_u16_le();
13364 let tmp = buf.get_u8();
13365 __struct.fix_type =
13366 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13367 enum_type: "GpsFixType",
13368 value: tmp as u32,
13369 })?;
13370 __struct.satellites_visible = buf.get_u8();
13371 __struct.dgps_numch = buf.get_u8();
13372 __struct.yaw = buf.get_u16_le();
13373 __struct.alt_ellipsoid = buf.get_i32_le();
13374 __struct.h_acc = buf.get_u32_le();
13375 __struct.v_acc = buf.get_u32_le();
13376 __struct.vel_acc = buf.get_u32_le();
13377 __struct.hdg_acc = buf.get_u32_le();
13378 Ok(__struct)
13379 }
13380 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13381 let mut __tmp = BytesMut::new(bytes);
13382 #[allow(clippy::absurd_extreme_comparisons)]
13383 #[allow(unused_comparisons)]
13384 if __tmp.remaining() < Self::ENCODED_LEN {
13385 panic!(
13386 "buffer is too small (need {} bytes, but got {})",
13387 Self::ENCODED_LEN,
13388 __tmp.remaining(),
13389 )
13390 }
13391 __tmp.put_u64_le(self.time_usec);
13392 __tmp.put_i32_le(self.lat);
13393 __tmp.put_i32_le(self.lon);
13394 __tmp.put_i32_le(self.alt);
13395 __tmp.put_u32_le(self.dgps_age);
13396 __tmp.put_u16_le(self.eph);
13397 __tmp.put_u16_le(self.epv);
13398 __tmp.put_u16_le(self.vel);
13399 __tmp.put_u16_le(self.cog);
13400 __tmp.put_u8(self.fix_type as u8);
13401 __tmp.put_u8(self.satellites_visible);
13402 __tmp.put_u8(self.dgps_numch);
13403 __tmp.put_u16_le(self.yaw);
13404 __tmp.put_i32_le(self.alt_ellipsoid);
13405 __tmp.put_u32_le(self.h_acc);
13406 __tmp.put_u32_le(self.v_acc);
13407 __tmp.put_u32_le(self.vel_acc);
13408 __tmp.put_u32_le(self.hdg_acc);
13409 if matches!(version, MavlinkVersion::V2) {
13410 let len = __tmp.len();
13411 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13412 } else {
13413 __tmp.len()
13414 }
13415 }
13416}
13417#[doc = "id: 128"]
13418#[doc = "RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting."]
13419#[derive(Debug, Clone, PartialEq)]
13420#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13421#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13422pub struct GPS2_RTK_DATA {
13423 #[doc = "Time since boot of last baseline message received."]
13424 pub time_last_baseline_ms: u32,
13425 #[doc = "GPS Time of Week of last baseline"]
13426 pub tow: u32,
13427 #[doc = "Current baseline in ECEF x or NED north component."]
13428 pub baseline_a_mm: i32,
13429 #[doc = "Current baseline in ECEF y or NED east component."]
13430 pub baseline_b_mm: i32,
13431 #[doc = "Current baseline in ECEF z or NED down component."]
13432 pub baseline_c_mm: i32,
13433 #[doc = "Current estimate of baseline accuracy."]
13434 pub accuracy: u32,
13435 #[doc = "Current number of integer ambiguity hypotheses."]
13436 pub iar_num_hypotheses: i32,
13437 #[doc = "GPS Week Number of last baseline"]
13438 pub wn: u16,
13439 #[doc = "Identification of connected RTK receiver."]
13440 pub rtk_receiver_id: u8,
13441 #[doc = "GPS-specific health report for RTK data."]
13442 pub rtk_health: u8,
13443 #[doc = "Rate of baseline messages being received by GPS"]
13444 pub rtk_rate: u8,
13445 #[doc = "Current number of sats used for RTK calculation."]
13446 pub nsats: u8,
13447 #[doc = "Coordinate system of baseline"]
13448 pub baseline_coords_type: RtkBaselineCoordinateSystem,
13449}
13450impl GPS2_RTK_DATA {
13451 pub const ENCODED_LEN: usize = 35usize;
13452 pub const DEFAULT: Self = Self {
13453 time_last_baseline_ms: 0_u32,
13454 tow: 0_u32,
13455 baseline_a_mm: 0_i32,
13456 baseline_b_mm: 0_i32,
13457 baseline_c_mm: 0_i32,
13458 accuracy: 0_u32,
13459 iar_num_hypotheses: 0_i32,
13460 wn: 0_u16,
13461 rtk_receiver_id: 0_u8,
13462 rtk_health: 0_u8,
13463 rtk_rate: 0_u8,
13464 nsats: 0_u8,
13465 baseline_coords_type: RtkBaselineCoordinateSystem::DEFAULT,
13466 };
13467 #[cfg(feature = "arbitrary")]
13468 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13469 use arbitrary::{Arbitrary, Unstructured};
13470 let mut buf = [0u8; 1024];
13471 rng.fill_bytes(&mut buf);
13472 let mut unstructured = Unstructured::new(&buf);
13473 Self::arbitrary(&mut unstructured).unwrap_or_default()
13474 }
13475}
13476impl Default for GPS2_RTK_DATA {
13477 fn default() -> Self {
13478 Self::DEFAULT.clone()
13479 }
13480}
13481impl MessageData for GPS2_RTK_DATA {
13482 type Message = MavMessage;
13483 const ID: u32 = 128u32;
13484 const NAME: &'static str = "GPS2_RTK";
13485 const EXTRA_CRC: u8 = 226u8;
13486 const ENCODED_LEN: usize = 35usize;
13487 fn deser(
13488 _version: MavlinkVersion,
13489 __input: &[u8],
13490 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13491 let avail_len = __input.len();
13492 let mut payload_buf = [0; Self::ENCODED_LEN];
13493 let mut buf = if avail_len < Self::ENCODED_LEN {
13494 payload_buf[0..avail_len].copy_from_slice(__input);
13495 Bytes::new(&payload_buf)
13496 } else {
13497 Bytes::new(__input)
13498 };
13499 let mut __struct = Self::default();
13500 __struct.time_last_baseline_ms = buf.get_u32_le();
13501 __struct.tow = buf.get_u32_le();
13502 __struct.baseline_a_mm = buf.get_i32_le();
13503 __struct.baseline_b_mm = buf.get_i32_le();
13504 __struct.baseline_c_mm = buf.get_i32_le();
13505 __struct.accuracy = buf.get_u32_le();
13506 __struct.iar_num_hypotheses = buf.get_i32_le();
13507 __struct.wn = buf.get_u16_le();
13508 __struct.rtk_receiver_id = buf.get_u8();
13509 __struct.rtk_health = buf.get_u8();
13510 __struct.rtk_rate = buf.get_u8();
13511 __struct.nsats = buf.get_u8();
13512 let tmp = buf.get_u8();
13513 __struct.baseline_coords_type =
13514 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13515 enum_type: "RtkBaselineCoordinateSystem",
13516 value: tmp as u32,
13517 })?;
13518 Ok(__struct)
13519 }
13520 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13521 let mut __tmp = BytesMut::new(bytes);
13522 #[allow(clippy::absurd_extreme_comparisons)]
13523 #[allow(unused_comparisons)]
13524 if __tmp.remaining() < Self::ENCODED_LEN {
13525 panic!(
13526 "buffer is too small (need {} bytes, but got {})",
13527 Self::ENCODED_LEN,
13528 __tmp.remaining(),
13529 )
13530 }
13531 __tmp.put_u32_le(self.time_last_baseline_ms);
13532 __tmp.put_u32_le(self.tow);
13533 __tmp.put_i32_le(self.baseline_a_mm);
13534 __tmp.put_i32_le(self.baseline_b_mm);
13535 __tmp.put_i32_le(self.baseline_c_mm);
13536 __tmp.put_u32_le(self.accuracy);
13537 __tmp.put_i32_le(self.iar_num_hypotheses);
13538 __tmp.put_u16_le(self.wn);
13539 __tmp.put_u8(self.rtk_receiver_id);
13540 __tmp.put_u8(self.rtk_health);
13541 __tmp.put_u8(self.rtk_rate);
13542 __tmp.put_u8(self.nsats);
13543 __tmp.put_u8(self.baseline_coords_type as u8);
13544 if matches!(version, MavlinkVersion::V2) {
13545 let len = __tmp.len();
13546 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13547 } else {
13548 __tmp.len()
13549 }
13550 }
13551}
13552#[doc = "id: 49"]
13553#[doc = "Publishes the GPS coordinates of the vehicle local origin (0,0,0) position. Emitted whenever a new GPS-Local position mapping is requested or set - e.g. following SET_GPS_GLOBAL_ORIGIN message."]
13554#[derive(Debug, Clone, PartialEq)]
13555#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13556#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13557pub struct GPS_GLOBAL_ORIGIN_DATA {
13558 #[doc = "Latitude (WGS84)"]
13559 pub latitude: i32,
13560 #[doc = "Longitude (WGS84)"]
13561 pub longitude: i32,
13562 #[doc = "Altitude (MSL). Positive for up."]
13563 pub altitude: i32,
13564 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
13565 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13566 pub time_usec: u64,
13567}
13568impl GPS_GLOBAL_ORIGIN_DATA {
13569 pub const ENCODED_LEN: usize = 20usize;
13570 pub const DEFAULT: Self = Self {
13571 latitude: 0_i32,
13572 longitude: 0_i32,
13573 altitude: 0_i32,
13574 time_usec: 0_u64,
13575 };
13576 #[cfg(feature = "arbitrary")]
13577 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13578 use arbitrary::{Arbitrary, Unstructured};
13579 let mut buf = [0u8; 1024];
13580 rng.fill_bytes(&mut buf);
13581 let mut unstructured = Unstructured::new(&buf);
13582 Self::arbitrary(&mut unstructured).unwrap_or_default()
13583 }
13584}
13585impl Default for GPS_GLOBAL_ORIGIN_DATA {
13586 fn default() -> Self {
13587 Self::DEFAULT.clone()
13588 }
13589}
13590impl MessageData for GPS_GLOBAL_ORIGIN_DATA {
13591 type Message = MavMessage;
13592 const ID: u32 = 49u32;
13593 const NAME: &'static str = "GPS_GLOBAL_ORIGIN";
13594 const EXTRA_CRC: u8 = 39u8;
13595 const ENCODED_LEN: usize = 20usize;
13596 fn deser(
13597 _version: MavlinkVersion,
13598 __input: &[u8],
13599 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13600 let avail_len = __input.len();
13601 let mut payload_buf = [0; Self::ENCODED_LEN];
13602 let mut buf = if avail_len < Self::ENCODED_LEN {
13603 payload_buf[0..avail_len].copy_from_slice(__input);
13604 Bytes::new(&payload_buf)
13605 } else {
13606 Bytes::new(__input)
13607 };
13608 let mut __struct = Self::default();
13609 __struct.latitude = buf.get_i32_le();
13610 __struct.longitude = buf.get_i32_le();
13611 __struct.altitude = buf.get_i32_le();
13612 __struct.time_usec = buf.get_u64_le();
13613 Ok(__struct)
13614 }
13615 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13616 let mut __tmp = BytesMut::new(bytes);
13617 #[allow(clippy::absurd_extreme_comparisons)]
13618 #[allow(unused_comparisons)]
13619 if __tmp.remaining() < Self::ENCODED_LEN {
13620 panic!(
13621 "buffer is too small (need {} bytes, but got {})",
13622 Self::ENCODED_LEN,
13623 __tmp.remaining(),
13624 )
13625 }
13626 __tmp.put_i32_le(self.latitude);
13627 __tmp.put_i32_le(self.longitude);
13628 __tmp.put_i32_le(self.altitude);
13629 __tmp.put_u64_le(self.time_usec);
13630 if matches!(version, MavlinkVersion::V2) {
13631 let len = __tmp.len();
13632 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13633 } else {
13634 __tmp.len()
13635 }
13636 }
13637}
13638#[doc = "id: 123"]
13639#[doc = "Data for injecting into the onboard GPS (used for DGPS)."]
13640#[derive(Debug, Clone, PartialEq)]
13641#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13642#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13643pub struct GPS_INJECT_DATA_DATA {
13644 #[doc = "System ID"]
13645 pub target_system: u8,
13646 #[doc = "Component ID"]
13647 pub target_component: u8,
13648 #[doc = "Data length"]
13649 pub len: u8,
13650 #[doc = "Raw data (110 is enough for 12 satellites of RTCMv2)"]
13651 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13652 pub data: [u8; 110],
13653}
13654impl GPS_INJECT_DATA_DATA {
13655 pub const ENCODED_LEN: usize = 113usize;
13656 pub const DEFAULT: Self = Self {
13657 target_system: 0_u8,
13658 target_component: 0_u8,
13659 len: 0_u8,
13660 data: [0_u8; 110usize],
13661 };
13662 #[cfg(feature = "arbitrary")]
13663 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13664 use arbitrary::{Arbitrary, Unstructured};
13665 let mut buf = [0u8; 1024];
13666 rng.fill_bytes(&mut buf);
13667 let mut unstructured = Unstructured::new(&buf);
13668 Self::arbitrary(&mut unstructured).unwrap_or_default()
13669 }
13670}
13671impl Default for GPS_INJECT_DATA_DATA {
13672 fn default() -> Self {
13673 Self::DEFAULT.clone()
13674 }
13675}
13676impl MessageData for GPS_INJECT_DATA_DATA {
13677 type Message = MavMessage;
13678 const ID: u32 = 123u32;
13679 const NAME: &'static str = "GPS_INJECT_DATA";
13680 const EXTRA_CRC: u8 = 250u8;
13681 const ENCODED_LEN: usize = 113usize;
13682 fn deser(
13683 _version: MavlinkVersion,
13684 __input: &[u8],
13685 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13686 let avail_len = __input.len();
13687 let mut payload_buf = [0; Self::ENCODED_LEN];
13688 let mut buf = if avail_len < Self::ENCODED_LEN {
13689 payload_buf[0..avail_len].copy_from_slice(__input);
13690 Bytes::new(&payload_buf)
13691 } else {
13692 Bytes::new(__input)
13693 };
13694 let mut __struct = Self::default();
13695 __struct.target_system = buf.get_u8();
13696 __struct.target_component = buf.get_u8();
13697 __struct.len = buf.get_u8();
13698 for v in &mut __struct.data {
13699 let val = buf.get_u8();
13700 *v = val;
13701 }
13702 Ok(__struct)
13703 }
13704 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13705 let mut __tmp = BytesMut::new(bytes);
13706 #[allow(clippy::absurd_extreme_comparisons)]
13707 #[allow(unused_comparisons)]
13708 if __tmp.remaining() < Self::ENCODED_LEN {
13709 panic!(
13710 "buffer is too small (need {} bytes, but got {})",
13711 Self::ENCODED_LEN,
13712 __tmp.remaining(),
13713 )
13714 }
13715 __tmp.put_u8(self.target_system);
13716 __tmp.put_u8(self.target_component);
13717 __tmp.put_u8(self.len);
13718 for val in &self.data {
13719 __tmp.put_u8(*val);
13720 }
13721 if matches!(version, MavlinkVersion::V2) {
13722 let len = __tmp.len();
13723 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13724 } else {
13725 __tmp.len()
13726 }
13727 }
13728}
13729#[doc = "id: 232"]
13730#[doc = "GPS sensor input message. This is a raw sensor value sent by the GPS. This is NOT the global position estimate of the system."]
13731#[derive(Debug, Clone, PartialEq)]
13732#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13733#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13734pub struct GPS_INPUT_DATA {
13735 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
13736 pub time_usec: u64,
13737 #[doc = "GPS time (from start of GPS week)"]
13738 pub time_week_ms: u32,
13739 #[doc = "Latitude (WGS84)"]
13740 pub lat: i32,
13741 #[doc = "Longitude (WGS84)"]
13742 pub lon: i32,
13743 #[doc = "Altitude (MSL). Positive for up."]
13744 pub alt: f32,
13745 #[doc = "GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX"]
13746 pub hdop: f32,
13747 #[doc = "GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX"]
13748 pub vdop: f32,
13749 #[doc = "GPS velocity in north direction in earth-fixed NED frame"]
13750 pub vn: f32,
13751 #[doc = "GPS velocity in east direction in earth-fixed NED frame"]
13752 pub ve: f32,
13753 #[doc = "GPS velocity in down direction in earth-fixed NED frame"]
13754 pub vd: f32,
13755 #[doc = "GPS speed accuracy"]
13756 pub speed_accuracy: f32,
13757 #[doc = "GPS horizontal accuracy"]
13758 pub horiz_accuracy: f32,
13759 #[doc = "GPS vertical accuracy"]
13760 pub vert_accuracy: f32,
13761 #[doc = "Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided."]
13762 pub ignore_flags: GpsInputIgnoreFlags,
13763 #[doc = "GPS week number"]
13764 pub time_week: u16,
13765 #[doc = "ID of the GPS for multiple GPS inputs"]
13766 pub gps_id: u8,
13767 #[doc = "0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK"]
13768 pub fix_type: u8,
13769 #[doc = "Number of satellites visible."]
13770 pub satellites_visible: u8,
13771 #[doc = "Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north"]
13772 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13773 pub yaw: u16,
13774}
13775impl GPS_INPUT_DATA {
13776 pub const ENCODED_LEN: usize = 65usize;
13777 pub const DEFAULT: Self = Self {
13778 time_usec: 0_u64,
13779 time_week_ms: 0_u32,
13780 lat: 0_i32,
13781 lon: 0_i32,
13782 alt: 0.0_f32,
13783 hdop: 0.0_f32,
13784 vdop: 0.0_f32,
13785 vn: 0.0_f32,
13786 ve: 0.0_f32,
13787 vd: 0.0_f32,
13788 speed_accuracy: 0.0_f32,
13789 horiz_accuracy: 0.0_f32,
13790 vert_accuracy: 0.0_f32,
13791 ignore_flags: GpsInputIgnoreFlags::DEFAULT,
13792 time_week: 0_u16,
13793 gps_id: 0_u8,
13794 fix_type: 0_u8,
13795 satellites_visible: 0_u8,
13796 yaw: 0_u16,
13797 };
13798 #[cfg(feature = "arbitrary")]
13799 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13800 use arbitrary::{Arbitrary, Unstructured};
13801 let mut buf = [0u8; 1024];
13802 rng.fill_bytes(&mut buf);
13803 let mut unstructured = Unstructured::new(&buf);
13804 Self::arbitrary(&mut unstructured).unwrap_or_default()
13805 }
13806}
13807impl Default for GPS_INPUT_DATA {
13808 fn default() -> Self {
13809 Self::DEFAULT.clone()
13810 }
13811}
13812impl MessageData for GPS_INPUT_DATA {
13813 type Message = MavMessage;
13814 const ID: u32 = 232u32;
13815 const NAME: &'static str = "GPS_INPUT";
13816 const EXTRA_CRC: u8 = 151u8;
13817 const ENCODED_LEN: usize = 65usize;
13818 fn deser(
13819 _version: MavlinkVersion,
13820 __input: &[u8],
13821 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13822 let avail_len = __input.len();
13823 let mut payload_buf = [0; Self::ENCODED_LEN];
13824 let mut buf = if avail_len < Self::ENCODED_LEN {
13825 payload_buf[0..avail_len].copy_from_slice(__input);
13826 Bytes::new(&payload_buf)
13827 } else {
13828 Bytes::new(__input)
13829 };
13830 let mut __struct = Self::default();
13831 __struct.time_usec = buf.get_u64_le();
13832 __struct.time_week_ms = buf.get_u32_le();
13833 __struct.lat = buf.get_i32_le();
13834 __struct.lon = buf.get_i32_le();
13835 __struct.alt = buf.get_f32_le();
13836 __struct.hdop = buf.get_f32_le();
13837 __struct.vdop = buf.get_f32_le();
13838 __struct.vn = buf.get_f32_le();
13839 __struct.ve = buf.get_f32_le();
13840 __struct.vd = buf.get_f32_le();
13841 __struct.speed_accuracy = buf.get_f32_le();
13842 __struct.horiz_accuracy = buf.get_f32_le();
13843 __struct.vert_accuracy = buf.get_f32_le();
13844 let tmp = buf.get_u16_le();
13845 __struct.ignore_flags = GpsInputIgnoreFlags::from_bits(
13846 tmp & GpsInputIgnoreFlags::all().bits(),
13847 )
13848 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
13849 flag_type: "GpsInputIgnoreFlags",
13850 value: tmp as u32,
13851 })?;
13852 __struct.time_week = buf.get_u16_le();
13853 __struct.gps_id = buf.get_u8();
13854 __struct.fix_type = buf.get_u8();
13855 __struct.satellites_visible = buf.get_u8();
13856 __struct.yaw = buf.get_u16_le();
13857 Ok(__struct)
13858 }
13859 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13860 let mut __tmp = BytesMut::new(bytes);
13861 #[allow(clippy::absurd_extreme_comparisons)]
13862 #[allow(unused_comparisons)]
13863 if __tmp.remaining() < Self::ENCODED_LEN {
13864 panic!(
13865 "buffer is too small (need {} bytes, but got {})",
13866 Self::ENCODED_LEN,
13867 __tmp.remaining(),
13868 )
13869 }
13870 __tmp.put_u64_le(self.time_usec);
13871 __tmp.put_u32_le(self.time_week_ms);
13872 __tmp.put_i32_le(self.lat);
13873 __tmp.put_i32_le(self.lon);
13874 __tmp.put_f32_le(self.alt);
13875 __tmp.put_f32_le(self.hdop);
13876 __tmp.put_f32_le(self.vdop);
13877 __tmp.put_f32_le(self.vn);
13878 __tmp.put_f32_le(self.ve);
13879 __tmp.put_f32_le(self.vd);
13880 __tmp.put_f32_le(self.speed_accuracy);
13881 __tmp.put_f32_le(self.horiz_accuracy);
13882 __tmp.put_f32_le(self.vert_accuracy);
13883 __tmp.put_u16_le(self.ignore_flags.bits());
13884 __tmp.put_u16_le(self.time_week);
13885 __tmp.put_u8(self.gps_id);
13886 __tmp.put_u8(self.fix_type);
13887 __tmp.put_u8(self.satellites_visible);
13888 __tmp.put_u16_le(self.yaw);
13889 if matches!(version, MavlinkVersion::V2) {
13890 let len = __tmp.len();
13891 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13892 } else {
13893 __tmp.len()
13894 }
13895 }
13896}
13897#[doc = "id: 24"]
13898#[doc = "The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate."]
13899#[derive(Debug, Clone, PartialEq)]
13900#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13901#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13902pub struct GPS_RAW_INT_DATA {
13903 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
13904 pub time_usec: u64,
13905 #[doc = "Latitude (WGS84, EGM96 ellipsoid)"]
13906 pub lat: i32,
13907 #[doc = "Longitude (WGS84, EGM96 ellipsoid)"]
13908 pub lon: i32,
13909 #[doc = "Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude."]
13910 pub alt: i32,
13911 #[doc = "GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
13912 pub eph: u16,
13913 #[doc = "GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
13914 pub epv: u16,
13915 #[doc = "GPS ground speed. If unknown, set to: UINT16_MAX"]
13916 pub vel: u16,
13917 #[doc = "Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
13918 pub cog: u16,
13919 #[doc = "GPS fix type."]
13920 pub fix_type: GpsFixType,
13921 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
13922 pub satellites_visible: u8,
13923 #[doc = "Altitude (above WGS84, EGM96 ellipsoid). Positive for up."]
13924 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13925 pub alt_ellipsoid: i32,
13926 #[doc = "Position uncertainty."]
13927 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13928 pub h_acc: u32,
13929 #[doc = "Altitude uncertainty."]
13930 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13931 pub v_acc: u32,
13932 #[doc = "Speed uncertainty."]
13933 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13934 pub vel_acc: u32,
13935 #[doc = "Heading / track uncertainty"]
13936 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13937 pub hdg_acc: u32,
13938 #[doc = "Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north."]
13939 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13940 pub yaw: u16,
13941}
13942impl GPS_RAW_INT_DATA {
13943 pub const ENCODED_LEN: usize = 52usize;
13944 pub const DEFAULT: Self = Self {
13945 time_usec: 0_u64,
13946 lat: 0_i32,
13947 lon: 0_i32,
13948 alt: 0_i32,
13949 eph: 0_u16,
13950 epv: 0_u16,
13951 vel: 0_u16,
13952 cog: 0_u16,
13953 fix_type: GpsFixType::DEFAULT,
13954 satellites_visible: 0_u8,
13955 alt_ellipsoid: 0_i32,
13956 h_acc: 0_u32,
13957 v_acc: 0_u32,
13958 vel_acc: 0_u32,
13959 hdg_acc: 0_u32,
13960 yaw: 0_u16,
13961 };
13962 #[cfg(feature = "arbitrary")]
13963 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13964 use arbitrary::{Arbitrary, Unstructured};
13965 let mut buf = [0u8; 1024];
13966 rng.fill_bytes(&mut buf);
13967 let mut unstructured = Unstructured::new(&buf);
13968 Self::arbitrary(&mut unstructured).unwrap_or_default()
13969 }
13970}
13971impl Default for GPS_RAW_INT_DATA {
13972 fn default() -> Self {
13973 Self::DEFAULT.clone()
13974 }
13975}
13976impl MessageData for GPS_RAW_INT_DATA {
13977 type Message = MavMessage;
13978 const ID: u32 = 24u32;
13979 const NAME: &'static str = "GPS_RAW_INT";
13980 const EXTRA_CRC: u8 = 24u8;
13981 const ENCODED_LEN: usize = 52usize;
13982 fn deser(
13983 _version: MavlinkVersion,
13984 __input: &[u8],
13985 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13986 let avail_len = __input.len();
13987 let mut payload_buf = [0; Self::ENCODED_LEN];
13988 let mut buf = if avail_len < Self::ENCODED_LEN {
13989 payload_buf[0..avail_len].copy_from_slice(__input);
13990 Bytes::new(&payload_buf)
13991 } else {
13992 Bytes::new(__input)
13993 };
13994 let mut __struct = Self::default();
13995 __struct.time_usec = buf.get_u64_le();
13996 __struct.lat = buf.get_i32_le();
13997 __struct.lon = buf.get_i32_le();
13998 __struct.alt = buf.get_i32_le();
13999 __struct.eph = buf.get_u16_le();
14000 __struct.epv = buf.get_u16_le();
14001 __struct.vel = buf.get_u16_le();
14002 __struct.cog = buf.get_u16_le();
14003 let tmp = buf.get_u8();
14004 __struct.fix_type =
14005 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
14006 enum_type: "GpsFixType",
14007 value: tmp as u32,
14008 })?;
14009 __struct.satellites_visible = buf.get_u8();
14010 __struct.alt_ellipsoid = buf.get_i32_le();
14011 __struct.h_acc = buf.get_u32_le();
14012 __struct.v_acc = buf.get_u32_le();
14013 __struct.vel_acc = buf.get_u32_le();
14014 __struct.hdg_acc = buf.get_u32_le();
14015 __struct.yaw = buf.get_u16_le();
14016 Ok(__struct)
14017 }
14018 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14019 let mut __tmp = BytesMut::new(bytes);
14020 #[allow(clippy::absurd_extreme_comparisons)]
14021 #[allow(unused_comparisons)]
14022 if __tmp.remaining() < Self::ENCODED_LEN {
14023 panic!(
14024 "buffer is too small (need {} bytes, but got {})",
14025 Self::ENCODED_LEN,
14026 __tmp.remaining(),
14027 )
14028 }
14029 __tmp.put_u64_le(self.time_usec);
14030 __tmp.put_i32_le(self.lat);
14031 __tmp.put_i32_le(self.lon);
14032 __tmp.put_i32_le(self.alt);
14033 __tmp.put_u16_le(self.eph);
14034 __tmp.put_u16_le(self.epv);
14035 __tmp.put_u16_le(self.vel);
14036 __tmp.put_u16_le(self.cog);
14037 __tmp.put_u8(self.fix_type as u8);
14038 __tmp.put_u8(self.satellites_visible);
14039 __tmp.put_i32_le(self.alt_ellipsoid);
14040 __tmp.put_u32_le(self.h_acc);
14041 __tmp.put_u32_le(self.v_acc);
14042 __tmp.put_u32_le(self.vel_acc);
14043 __tmp.put_u32_le(self.hdg_acc);
14044 __tmp.put_u16_le(self.yaw);
14045 if matches!(version, MavlinkVersion::V2) {
14046 let len = __tmp.len();
14047 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14048 } else {
14049 __tmp.len()
14050 }
14051 }
14052}
14053#[doc = "id: 233"]
14054#[doc = "RTCM message for injecting into the onboard GPS (used for DGPS)."]
14055#[derive(Debug, Clone, PartialEq)]
14056#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14057#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14058pub struct GPS_RTCM_DATA_DATA {
14059 #[doc = "LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order."]
14060 pub flags: u8,
14061 #[doc = "data length"]
14062 pub len: u8,
14063 #[doc = "RTCM message (may be fragmented)"]
14064 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14065 pub data: [u8; 180],
14066}
14067impl GPS_RTCM_DATA_DATA {
14068 pub const ENCODED_LEN: usize = 182usize;
14069 pub const DEFAULT: Self = Self {
14070 flags: 0_u8,
14071 len: 0_u8,
14072 data: [0_u8; 180usize],
14073 };
14074 #[cfg(feature = "arbitrary")]
14075 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14076 use arbitrary::{Arbitrary, Unstructured};
14077 let mut buf = [0u8; 1024];
14078 rng.fill_bytes(&mut buf);
14079 let mut unstructured = Unstructured::new(&buf);
14080 Self::arbitrary(&mut unstructured).unwrap_or_default()
14081 }
14082}
14083impl Default for GPS_RTCM_DATA_DATA {
14084 fn default() -> Self {
14085 Self::DEFAULT.clone()
14086 }
14087}
14088impl MessageData for GPS_RTCM_DATA_DATA {
14089 type Message = MavMessage;
14090 const ID: u32 = 233u32;
14091 const NAME: &'static str = "GPS_RTCM_DATA";
14092 const EXTRA_CRC: u8 = 35u8;
14093 const ENCODED_LEN: usize = 182usize;
14094 fn deser(
14095 _version: MavlinkVersion,
14096 __input: &[u8],
14097 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14098 let avail_len = __input.len();
14099 let mut payload_buf = [0; Self::ENCODED_LEN];
14100 let mut buf = if avail_len < Self::ENCODED_LEN {
14101 payload_buf[0..avail_len].copy_from_slice(__input);
14102 Bytes::new(&payload_buf)
14103 } else {
14104 Bytes::new(__input)
14105 };
14106 let mut __struct = Self::default();
14107 __struct.flags = buf.get_u8();
14108 __struct.len = buf.get_u8();
14109 for v in &mut __struct.data {
14110 let val = buf.get_u8();
14111 *v = val;
14112 }
14113 Ok(__struct)
14114 }
14115 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14116 let mut __tmp = BytesMut::new(bytes);
14117 #[allow(clippy::absurd_extreme_comparisons)]
14118 #[allow(unused_comparisons)]
14119 if __tmp.remaining() < Self::ENCODED_LEN {
14120 panic!(
14121 "buffer is too small (need {} bytes, but got {})",
14122 Self::ENCODED_LEN,
14123 __tmp.remaining(),
14124 )
14125 }
14126 __tmp.put_u8(self.flags);
14127 __tmp.put_u8(self.len);
14128 for val in &self.data {
14129 __tmp.put_u8(*val);
14130 }
14131 if matches!(version, MavlinkVersion::V2) {
14132 let len = __tmp.len();
14133 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14134 } else {
14135 __tmp.len()
14136 }
14137 }
14138}
14139#[doc = "id: 127"]
14140#[doc = "RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting."]
14141#[derive(Debug, Clone, PartialEq)]
14142#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14143#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14144pub struct GPS_RTK_DATA {
14145 #[doc = "Time since boot of last baseline message received."]
14146 pub time_last_baseline_ms: u32,
14147 #[doc = "GPS Time of Week of last baseline"]
14148 pub tow: u32,
14149 #[doc = "Current baseline in ECEF x or NED north component."]
14150 pub baseline_a_mm: i32,
14151 #[doc = "Current baseline in ECEF y or NED east component."]
14152 pub baseline_b_mm: i32,
14153 #[doc = "Current baseline in ECEF z or NED down component."]
14154 pub baseline_c_mm: i32,
14155 #[doc = "Current estimate of baseline accuracy."]
14156 pub accuracy: u32,
14157 #[doc = "Current number of integer ambiguity hypotheses."]
14158 pub iar_num_hypotheses: i32,
14159 #[doc = "GPS Week Number of last baseline"]
14160 pub wn: u16,
14161 #[doc = "Identification of connected RTK receiver."]
14162 pub rtk_receiver_id: u8,
14163 #[doc = "GPS-specific health report for RTK data."]
14164 pub rtk_health: u8,
14165 #[doc = "Rate of baseline messages being received by GPS"]
14166 pub rtk_rate: u8,
14167 #[doc = "Current number of sats used for RTK calculation."]
14168 pub nsats: u8,
14169 #[doc = "Coordinate system of baseline"]
14170 pub baseline_coords_type: RtkBaselineCoordinateSystem,
14171}
14172impl GPS_RTK_DATA {
14173 pub const ENCODED_LEN: usize = 35usize;
14174 pub const DEFAULT: Self = Self {
14175 time_last_baseline_ms: 0_u32,
14176 tow: 0_u32,
14177 baseline_a_mm: 0_i32,
14178 baseline_b_mm: 0_i32,
14179 baseline_c_mm: 0_i32,
14180 accuracy: 0_u32,
14181 iar_num_hypotheses: 0_i32,
14182 wn: 0_u16,
14183 rtk_receiver_id: 0_u8,
14184 rtk_health: 0_u8,
14185 rtk_rate: 0_u8,
14186 nsats: 0_u8,
14187 baseline_coords_type: RtkBaselineCoordinateSystem::DEFAULT,
14188 };
14189 #[cfg(feature = "arbitrary")]
14190 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14191 use arbitrary::{Arbitrary, Unstructured};
14192 let mut buf = [0u8; 1024];
14193 rng.fill_bytes(&mut buf);
14194 let mut unstructured = Unstructured::new(&buf);
14195 Self::arbitrary(&mut unstructured).unwrap_or_default()
14196 }
14197}
14198impl Default for GPS_RTK_DATA {
14199 fn default() -> Self {
14200 Self::DEFAULT.clone()
14201 }
14202}
14203impl MessageData for GPS_RTK_DATA {
14204 type Message = MavMessage;
14205 const ID: u32 = 127u32;
14206 const NAME: &'static str = "GPS_RTK";
14207 const EXTRA_CRC: u8 = 25u8;
14208 const ENCODED_LEN: usize = 35usize;
14209 fn deser(
14210 _version: MavlinkVersion,
14211 __input: &[u8],
14212 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14213 let avail_len = __input.len();
14214 let mut payload_buf = [0; Self::ENCODED_LEN];
14215 let mut buf = if avail_len < Self::ENCODED_LEN {
14216 payload_buf[0..avail_len].copy_from_slice(__input);
14217 Bytes::new(&payload_buf)
14218 } else {
14219 Bytes::new(__input)
14220 };
14221 let mut __struct = Self::default();
14222 __struct.time_last_baseline_ms = buf.get_u32_le();
14223 __struct.tow = buf.get_u32_le();
14224 __struct.baseline_a_mm = buf.get_i32_le();
14225 __struct.baseline_b_mm = buf.get_i32_le();
14226 __struct.baseline_c_mm = buf.get_i32_le();
14227 __struct.accuracy = buf.get_u32_le();
14228 __struct.iar_num_hypotheses = buf.get_i32_le();
14229 __struct.wn = buf.get_u16_le();
14230 __struct.rtk_receiver_id = buf.get_u8();
14231 __struct.rtk_health = buf.get_u8();
14232 __struct.rtk_rate = buf.get_u8();
14233 __struct.nsats = buf.get_u8();
14234 let tmp = buf.get_u8();
14235 __struct.baseline_coords_type =
14236 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
14237 enum_type: "RtkBaselineCoordinateSystem",
14238 value: tmp as u32,
14239 })?;
14240 Ok(__struct)
14241 }
14242 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14243 let mut __tmp = BytesMut::new(bytes);
14244 #[allow(clippy::absurd_extreme_comparisons)]
14245 #[allow(unused_comparisons)]
14246 if __tmp.remaining() < Self::ENCODED_LEN {
14247 panic!(
14248 "buffer is too small (need {} bytes, but got {})",
14249 Self::ENCODED_LEN,
14250 __tmp.remaining(),
14251 )
14252 }
14253 __tmp.put_u32_le(self.time_last_baseline_ms);
14254 __tmp.put_u32_le(self.tow);
14255 __tmp.put_i32_le(self.baseline_a_mm);
14256 __tmp.put_i32_le(self.baseline_b_mm);
14257 __tmp.put_i32_le(self.baseline_c_mm);
14258 __tmp.put_u32_le(self.accuracy);
14259 __tmp.put_i32_le(self.iar_num_hypotheses);
14260 __tmp.put_u16_le(self.wn);
14261 __tmp.put_u8(self.rtk_receiver_id);
14262 __tmp.put_u8(self.rtk_health);
14263 __tmp.put_u8(self.rtk_rate);
14264 __tmp.put_u8(self.nsats);
14265 __tmp.put_u8(self.baseline_coords_type as u8);
14266 if matches!(version, MavlinkVersion::V2) {
14267 let len = __tmp.len();
14268 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14269 } else {
14270 __tmp.len()
14271 }
14272 }
14273}
14274#[doc = "id: 25"]
14275#[doc = "The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION_INT for the global position estimate. This message can contain information for up to 20 satellites."]
14276#[derive(Debug, Clone, PartialEq)]
14277#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14278#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14279pub struct GPS_STATUS_DATA {
14280 #[doc = "Number of satellites visible"]
14281 pub satellites_visible: u8,
14282 #[doc = "Global satellite ID"]
14283 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14284 pub satellite_prn: [u8; 20],
14285 #[doc = "0: Satellite not used, 1: used for localization"]
14286 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14287 pub satellite_used: [u8; 20],
14288 #[doc = "Elevation (0: right on top of receiver, 90: on the horizon) of satellite"]
14289 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14290 pub satellite_elevation: [u8; 20],
14291 #[doc = "Direction of satellite, 0: 0 deg, 255: 360 deg."]
14292 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14293 pub satellite_azimuth: [u8; 20],
14294 #[doc = "Signal to noise ratio of satellite"]
14295 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14296 pub satellite_snr: [u8; 20],
14297}
14298impl GPS_STATUS_DATA {
14299 pub const ENCODED_LEN: usize = 101usize;
14300 pub const DEFAULT: Self = Self {
14301 satellites_visible: 0_u8,
14302 satellite_prn: [0_u8; 20usize],
14303 satellite_used: [0_u8; 20usize],
14304 satellite_elevation: [0_u8; 20usize],
14305 satellite_azimuth: [0_u8; 20usize],
14306 satellite_snr: [0_u8; 20usize],
14307 };
14308 #[cfg(feature = "arbitrary")]
14309 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14310 use arbitrary::{Arbitrary, Unstructured};
14311 let mut buf = [0u8; 1024];
14312 rng.fill_bytes(&mut buf);
14313 let mut unstructured = Unstructured::new(&buf);
14314 Self::arbitrary(&mut unstructured).unwrap_or_default()
14315 }
14316}
14317impl Default for GPS_STATUS_DATA {
14318 fn default() -> Self {
14319 Self::DEFAULT.clone()
14320 }
14321}
14322impl MessageData for GPS_STATUS_DATA {
14323 type Message = MavMessage;
14324 const ID: u32 = 25u32;
14325 const NAME: &'static str = "GPS_STATUS";
14326 const EXTRA_CRC: u8 = 23u8;
14327 const ENCODED_LEN: usize = 101usize;
14328 fn deser(
14329 _version: MavlinkVersion,
14330 __input: &[u8],
14331 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14332 let avail_len = __input.len();
14333 let mut payload_buf = [0; Self::ENCODED_LEN];
14334 let mut buf = if avail_len < Self::ENCODED_LEN {
14335 payload_buf[0..avail_len].copy_from_slice(__input);
14336 Bytes::new(&payload_buf)
14337 } else {
14338 Bytes::new(__input)
14339 };
14340 let mut __struct = Self::default();
14341 __struct.satellites_visible = buf.get_u8();
14342 for v in &mut __struct.satellite_prn {
14343 let val = buf.get_u8();
14344 *v = val;
14345 }
14346 for v in &mut __struct.satellite_used {
14347 let val = buf.get_u8();
14348 *v = val;
14349 }
14350 for v in &mut __struct.satellite_elevation {
14351 let val = buf.get_u8();
14352 *v = val;
14353 }
14354 for v in &mut __struct.satellite_azimuth {
14355 let val = buf.get_u8();
14356 *v = val;
14357 }
14358 for v in &mut __struct.satellite_snr {
14359 let val = buf.get_u8();
14360 *v = val;
14361 }
14362 Ok(__struct)
14363 }
14364 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14365 let mut __tmp = BytesMut::new(bytes);
14366 #[allow(clippy::absurd_extreme_comparisons)]
14367 #[allow(unused_comparisons)]
14368 if __tmp.remaining() < Self::ENCODED_LEN {
14369 panic!(
14370 "buffer is too small (need {} bytes, but got {})",
14371 Self::ENCODED_LEN,
14372 __tmp.remaining(),
14373 )
14374 }
14375 __tmp.put_u8(self.satellites_visible);
14376 for val in &self.satellite_prn {
14377 __tmp.put_u8(*val);
14378 }
14379 for val in &self.satellite_used {
14380 __tmp.put_u8(*val);
14381 }
14382 for val in &self.satellite_elevation {
14383 __tmp.put_u8(*val);
14384 }
14385 for val in &self.satellite_azimuth {
14386 __tmp.put_u8(*val);
14387 }
14388 for val in &self.satellite_snr {
14389 __tmp.put_u8(*val);
14390 }
14391 if matches!(version, MavlinkVersion::V2) {
14392 let len = __tmp.len();
14393 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14394 } else {
14395 __tmp.len()
14396 }
14397 }
14398}
14399#[doc = "id: 0"]
14400#[doc = "The heartbeat message shows that a system or component is present and responding. The type and autopilot fields (along with the message component id), allow the receiving system to treat further messages from this system appropriately (e.g. by laying out the user interface based on the autopilot). This microservice is documented at <https://mavlink.io/en/services/heartbeat.html>."]
14401#[derive(Debug, Clone, PartialEq)]
14402#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14403#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14404pub struct HEARTBEAT_DATA {
14405 #[doc = "A bitfield for use for autopilot-specific flags"]
14406 pub custom_mode: u32,
14407 #[doc = "Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type."]
14408 pub mavtype: MavType,
14409 #[doc = "Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers."]
14410 pub autopilot: MavAutopilot,
14411 #[doc = "System mode bitmap."]
14412 pub base_mode: MavModeFlag,
14413 #[doc = "System status flag."]
14414 pub system_status: MavState,
14415 #[doc = "MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version"]
14416 pub mavlink_version: u8,
14417}
14418impl HEARTBEAT_DATA {
14419 pub const ENCODED_LEN: usize = 9usize;
14420 pub const DEFAULT: Self = Self {
14421 custom_mode: 0_u32,
14422 mavtype: MavType::DEFAULT,
14423 autopilot: MavAutopilot::DEFAULT,
14424 base_mode: MavModeFlag::DEFAULT,
14425 system_status: MavState::DEFAULT,
14426 mavlink_version: 0_u8,
14427 };
14428 #[cfg(feature = "arbitrary")]
14429 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14430 use arbitrary::{Arbitrary, Unstructured};
14431 let mut buf = [0u8; 1024];
14432 rng.fill_bytes(&mut buf);
14433 let mut unstructured = Unstructured::new(&buf);
14434 Self::arbitrary(&mut unstructured).unwrap_or_default()
14435 }
14436}
14437impl Default for HEARTBEAT_DATA {
14438 fn default() -> Self {
14439 Self::DEFAULT.clone()
14440 }
14441}
14442impl MessageData for HEARTBEAT_DATA {
14443 type Message = MavMessage;
14444 const ID: u32 = 0u32;
14445 const NAME: &'static str = "HEARTBEAT";
14446 const EXTRA_CRC: u8 = 50u8;
14447 const ENCODED_LEN: usize = 9usize;
14448 fn deser(
14449 _version: MavlinkVersion,
14450 __input: &[u8],
14451 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14452 let avail_len = __input.len();
14453 let mut payload_buf = [0; Self::ENCODED_LEN];
14454 let mut buf = if avail_len < Self::ENCODED_LEN {
14455 payload_buf[0..avail_len].copy_from_slice(__input);
14456 Bytes::new(&payload_buf)
14457 } else {
14458 Bytes::new(__input)
14459 };
14460 let mut __struct = Self::default();
14461 __struct.custom_mode = buf.get_u32_le();
14462 let tmp = buf.get_u8();
14463 __struct.mavtype =
14464 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
14465 enum_type: "MavType",
14466 value: tmp as u32,
14467 })?;
14468 let tmp = buf.get_u8();
14469 __struct.autopilot =
14470 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
14471 enum_type: "MavAutopilot",
14472 value: tmp as u32,
14473 })?;
14474 let tmp = buf.get_u8();
14475 __struct.base_mode = MavModeFlag::from_bits(tmp & MavModeFlag::all().bits()).ok_or(
14476 ::mavlink_core::error::ParserError::InvalidFlag {
14477 flag_type: "MavModeFlag",
14478 value: tmp as u32,
14479 },
14480 )?;
14481 let tmp = buf.get_u8();
14482 __struct.system_status =
14483 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
14484 enum_type: "MavState",
14485 value: tmp as u32,
14486 })?;
14487 __struct.mavlink_version = buf.get_u8();
14488 Ok(__struct)
14489 }
14490 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14491 let mut __tmp = BytesMut::new(bytes);
14492 #[allow(clippy::absurd_extreme_comparisons)]
14493 #[allow(unused_comparisons)]
14494 if __tmp.remaining() < Self::ENCODED_LEN {
14495 panic!(
14496 "buffer is too small (need {} bytes, but got {})",
14497 Self::ENCODED_LEN,
14498 __tmp.remaining(),
14499 )
14500 }
14501 __tmp.put_u32_le(self.custom_mode);
14502 __tmp.put_u8(self.mavtype as u8);
14503 __tmp.put_u8(self.autopilot as u8);
14504 __tmp.put_u8(self.base_mode.bits());
14505 __tmp.put_u8(self.system_status as u8);
14506 __tmp.put_u8(self.mavlink_version);
14507 if matches!(version, MavlinkVersion::V2) {
14508 let len = __tmp.len();
14509 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14510 } else {
14511 __tmp.len()
14512 }
14513 }
14514}
14515#[doc = "id: 105"]
14516#[doc = "The IMU readings in SI units in NED body frame."]
14517#[derive(Debug, Clone, PartialEq)]
14518#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14519#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14520pub struct HIGHRES_IMU_DATA {
14521 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
14522 pub time_usec: u64,
14523 #[doc = "X acceleration"]
14524 pub xacc: f32,
14525 #[doc = "Y acceleration"]
14526 pub yacc: f32,
14527 #[doc = "Z acceleration"]
14528 pub zacc: f32,
14529 #[doc = "Angular speed around X axis"]
14530 pub xgyro: f32,
14531 #[doc = "Angular speed around Y axis"]
14532 pub ygyro: f32,
14533 #[doc = "Angular speed around Z axis"]
14534 pub zgyro: f32,
14535 #[doc = "X Magnetic field"]
14536 pub xmag: f32,
14537 #[doc = "Y Magnetic field"]
14538 pub ymag: f32,
14539 #[doc = "Z Magnetic field"]
14540 pub zmag: f32,
14541 #[doc = "Absolute pressure"]
14542 pub abs_pressure: f32,
14543 #[doc = "Differential pressure"]
14544 pub diff_pressure: f32,
14545 #[doc = "Altitude calculated from pressure"]
14546 pub pressure_alt: f32,
14547 #[doc = "Temperature"]
14548 pub temperature: f32,
14549 #[doc = "Bitmap for fields that have updated since last message"]
14550 pub fields_updated: HighresImuUpdatedFlags,
14551 #[doc = "Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)"]
14552 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
14553 pub id: u8,
14554}
14555impl HIGHRES_IMU_DATA {
14556 pub const ENCODED_LEN: usize = 63usize;
14557 pub const DEFAULT: Self = Self {
14558 time_usec: 0_u64,
14559 xacc: 0.0_f32,
14560 yacc: 0.0_f32,
14561 zacc: 0.0_f32,
14562 xgyro: 0.0_f32,
14563 ygyro: 0.0_f32,
14564 zgyro: 0.0_f32,
14565 xmag: 0.0_f32,
14566 ymag: 0.0_f32,
14567 zmag: 0.0_f32,
14568 abs_pressure: 0.0_f32,
14569 diff_pressure: 0.0_f32,
14570 pressure_alt: 0.0_f32,
14571 temperature: 0.0_f32,
14572 fields_updated: HighresImuUpdatedFlags::DEFAULT,
14573 id: 0_u8,
14574 };
14575 #[cfg(feature = "arbitrary")]
14576 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14577 use arbitrary::{Arbitrary, Unstructured};
14578 let mut buf = [0u8; 1024];
14579 rng.fill_bytes(&mut buf);
14580 let mut unstructured = Unstructured::new(&buf);
14581 Self::arbitrary(&mut unstructured).unwrap_or_default()
14582 }
14583}
14584impl Default for HIGHRES_IMU_DATA {
14585 fn default() -> Self {
14586 Self::DEFAULT.clone()
14587 }
14588}
14589impl MessageData for HIGHRES_IMU_DATA {
14590 type Message = MavMessage;
14591 const ID: u32 = 105u32;
14592 const NAME: &'static str = "HIGHRES_IMU";
14593 const EXTRA_CRC: u8 = 93u8;
14594 const ENCODED_LEN: usize = 63usize;
14595 fn deser(
14596 _version: MavlinkVersion,
14597 __input: &[u8],
14598 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14599 let avail_len = __input.len();
14600 let mut payload_buf = [0; Self::ENCODED_LEN];
14601 let mut buf = if avail_len < Self::ENCODED_LEN {
14602 payload_buf[0..avail_len].copy_from_slice(__input);
14603 Bytes::new(&payload_buf)
14604 } else {
14605 Bytes::new(__input)
14606 };
14607 let mut __struct = Self::default();
14608 __struct.time_usec = buf.get_u64_le();
14609 __struct.xacc = buf.get_f32_le();
14610 __struct.yacc = buf.get_f32_le();
14611 __struct.zacc = buf.get_f32_le();
14612 __struct.xgyro = buf.get_f32_le();
14613 __struct.ygyro = buf.get_f32_le();
14614 __struct.zgyro = buf.get_f32_le();
14615 __struct.xmag = buf.get_f32_le();
14616 __struct.ymag = buf.get_f32_le();
14617 __struct.zmag = buf.get_f32_le();
14618 __struct.abs_pressure = buf.get_f32_le();
14619 __struct.diff_pressure = buf.get_f32_le();
14620 __struct.pressure_alt = buf.get_f32_le();
14621 __struct.temperature = buf.get_f32_le();
14622 let tmp = buf.get_u16_le();
14623 __struct.fields_updated = HighresImuUpdatedFlags::from_bits(
14624 tmp & HighresImuUpdatedFlags::all().bits(),
14625 )
14626 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
14627 flag_type: "HighresImuUpdatedFlags",
14628 value: tmp as u32,
14629 })?;
14630 __struct.id = buf.get_u8();
14631 Ok(__struct)
14632 }
14633 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14634 let mut __tmp = BytesMut::new(bytes);
14635 #[allow(clippy::absurd_extreme_comparisons)]
14636 #[allow(unused_comparisons)]
14637 if __tmp.remaining() < Self::ENCODED_LEN {
14638 panic!(
14639 "buffer is too small (need {} bytes, but got {})",
14640 Self::ENCODED_LEN,
14641 __tmp.remaining(),
14642 )
14643 }
14644 __tmp.put_u64_le(self.time_usec);
14645 __tmp.put_f32_le(self.xacc);
14646 __tmp.put_f32_le(self.yacc);
14647 __tmp.put_f32_le(self.zacc);
14648 __tmp.put_f32_le(self.xgyro);
14649 __tmp.put_f32_le(self.ygyro);
14650 __tmp.put_f32_le(self.zgyro);
14651 __tmp.put_f32_le(self.xmag);
14652 __tmp.put_f32_le(self.ymag);
14653 __tmp.put_f32_le(self.zmag);
14654 __tmp.put_f32_le(self.abs_pressure);
14655 __tmp.put_f32_le(self.diff_pressure);
14656 __tmp.put_f32_le(self.pressure_alt);
14657 __tmp.put_f32_le(self.temperature);
14658 __tmp.put_u16_le(self.fields_updated.bits());
14659 __tmp.put_u8(self.id);
14660 if matches!(version, MavlinkVersion::V2) {
14661 let len = __tmp.len();
14662 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14663 } else {
14664 __tmp.len()
14665 }
14666 }
14667}
14668#[doc = "id: 234"]
14669#[doc = "Message appropriate for high latency connections like Iridium."]
14670#[derive(Debug, Clone, PartialEq)]
14671#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14672#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14673pub struct HIGH_LATENCY_DATA {
14674 #[doc = "A bitfield for use for autopilot-specific flags."]
14675 pub custom_mode: u32,
14676 #[doc = "Latitude"]
14677 pub latitude: i32,
14678 #[doc = "Longitude"]
14679 pub longitude: i32,
14680 #[doc = "roll"]
14681 pub roll: i16,
14682 #[doc = "pitch"]
14683 pub pitch: i16,
14684 #[doc = "heading"]
14685 pub heading: u16,
14686 #[doc = "heading setpoint"]
14687 pub heading_sp: i16,
14688 #[doc = "Altitude above mean sea level"]
14689 pub altitude_amsl: i16,
14690 #[doc = "Altitude setpoint relative to the home position"]
14691 pub altitude_sp: i16,
14692 #[doc = "distance to target"]
14693 pub wp_distance: u16,
14694 #[doc = "Bitmap of enabled system modes."]
14695 pub base_mode: MavModeFlag,
14696 #[doc = "The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown."]
14697 pub landed_state: MavLandedState,
14698 #[doc = "throttle (percentage)"]
14699 pub throttle: i8,
14700 #[doc = "airspeed"]
14701 pub airspeed: u8,
14702 #[doc = "airspeed setpoint"]
14703 pub airspeed_sp: u8,
14704 #[doc = "groundspeed"]
14705 pub groundspeed: u8,
14706 #[doc = "climb rate"]
14707 pub climb_rate: i8,
14708 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
14709 pub gps_nsat: u8,
14710 #[doc = "GPS Fix type."]
14711 pub gps_fix_type: GpsFixType,
14712 #[doc = "Remaining battery (percentage)"]
14713 pub battery_remaining: u8,
14714 #[doc = "Autopilot temperature (degrees C)"]
14715 pub temperature: i8,
14716 #[doc = "Air temperature (degrees C) from airspeed sensor"]
14717 pub temperature_air: i8,
14718 #[doc = "failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)"]
14719 pub failsafe: u8,
14720 #[doc = "current waypoint number"]
14721 pub wp_num: u8,
14722}
14723impl HIGH_LATENCY_DATA {
14724 pub const ENCODED_LEN: usize = 40usize;
14725 pub const DEFAULT: Self = Self {
14726 custom_mode: 0_u32,
14727 latitude: 0_i32,
14728 longitude: 0_i32,
14729 roll: 0_i16,
14730 pitch: 0_i16,
14731 heading: 0_u16,
14732 heading_sp: 0_i16,
14733 altitude_amsl: 0_i16,
14734 altitude_sp: 0_i16,
14735 wp_distance: 0_u16,
14736 base_mode: MavModeFlag::DEFAULT,
14737 landed_state: MavLandedState::DEFAULT,
14738 throttle: 0_i8,
14739 airspeed: 0_u8,
14740 airspeed_sp: 0_u8,
14741 groundspeed: 0_u8,
14742 climb_rate: 0_i8,
14743 gps_nsat: 0_u8,
14744 gps_fix_type: GpsFixType::DEFAULT,
14745 battery_remaining: 0_u8,
14746 temperature: 0_i8,
14747 temperature_air: 0_i8,
14748 failsafe: 0_u8,
14749 wp_num: 0_u8,
14750 };
14751 #[cfg(feature = "arbitrary")]
14752 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14753 use arbitrary::{Arbitrary, Unstructured};
14754 let mut buf = [0u8; 1024];
14755 rng.fill_bytes(&mut buf);
14756 let mut unstructured = Unstructured::new(&buf);
14757 Self::arbitrary(&mut unstructured).unwrap_or_default()
14758 }
14759}
14760impl Default for HIGH_LATENCY_DATA {
14761 fn default() -> Self {
14762 Self::DEFAULT.clone()
14763 }
14764}
14765impl MessageData for HIGH_LATENCY_DATA {
14766 type Message = MavMessage;
14767 const ID: u32 = 234u32;
14768 const NAME: &'static str = "HIGH_LATENCY";
14769 const EXTRA_CRC: u8 = 150u8;
14770 const ENCODED_LEN: usize = 40usize;
14771 fn deser(
14772 _version: MavlinkVersion,
14773 __input: &[u8],
14774 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14775 let avail_len = __input.len();
14776 let mut payload_buf = [0; Self::ENCODED_LEN];
14777 let mut buf = if avail_len < Self::ENCODED_LEN {
14778 payload_buf[0..avail_len].copy_from_slice(__input);
14779 Bytes::new(&payload_buf)
14780 } else {
14781 Bytes::new(__input)
14782 };
14783 let mut __struct = Self::default();
14784 __struct.custom_mode = buf.get_u32_le();
14785 __struct.latitude = buf.get_i32_le();
14786 __struct.longitude = buf.get_i32_le();
14787 __struct.roll = buf.get_i16_le();
14788 __struct.pitch = buf.get_i16_le();
14789 __struct.heading = buf.get_u16_le();
14790 __struct.heading_sp = buf.get_i16_le();
14791 __struct.altitude_amsl = buf.get_i16_le();
14792 __struct.altitude_sp = buf.get_i16_le();
14793 __struct.wp_distance = buf.get_u16_le();
14794 let tmp = buf.get_u8();
14795 __struct.base_mode = MavModeFlag::from_bits(tmp & MavModeFlag::all().bits()).ok_or(
14796 ::mavlink_core::error::ParserError::InvalidFlag {
14797 flag_type: "MavModeFlag",
14798 value: tmp as u32,
14799 },
14800 )?;
14801 let tmp = buf.get_u8();
14802 __struct.landed_state =
14803 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
14804 enum_type: "MavLandedState",
14805 value: tmp as u32,
14806 })?;
14807 __struct.throttle = buf.get_i8();
14808 __struct.airspeed = buf.get_u8();
14809 __struct.airspeed_sp = buf.get_u8();
14810 __struct.groundspeed = buf.get_u8();
14811 __struct.climb_rate = buf.get_i8();
14812 __struct.gps_nsat = buf.get_u8();
14813 let tmp = buf.get_u8();
14814 __struct.gps_fix_type =
14815 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
14816 enum_type: "GpsFixType",
14817 value: tmp as u32,
14818 })?;
14819 __struct.battery_remaining = buf.get_u8();
14820 __struct.temperature = buf.get_i8();
14821 __struct.temperature_air = buf.get_i8();
14822 __struct.failsafe = buf.get_u8();
14823 __struct.wp_num = buf.get_u8();
14824 Ok(__struct)
14825 }
14826 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14827 let mut __tmp = BytesMut::new(bytes);
14828 #[allow(clippy::absurd_extreme_comparisons)]
14829 #[allow(unused_comparisons)]
14830 if __tmp.remaining() < Self::ENCODED_LEN {
14831 panic!(
14832 "buffer is too small (need {} bytes, but got {})",
14833 Self::ENCODED_LEN,
14834 __tmp.remaining(),
14835 )
14836 }
14837 __tmp.put_u32_le(self.custom_mode);
14838 __tmp.put_i32_le(self.latitude);
14839 __tmp.put_i32_le(self.longitude);
14840 __tmp.put_i16_le(self.roll);
14841 __tmp.put_i16_le(self.pitch);
14842 __tmp.put_u16_le(self.heading);
14843 __tmp.put_i16_le(self.heading_sp);
14844 __tmp.put_i16_le(self.altitude_amsl);
14845 __tmp.put_i16_le(self.altitude_sp);
14846 __tmp.put_u16_le(self.wp_distance);
14847 __tmp.put_u8(self.base_mode.bits());
14848 __tmp.put_u8(self.landed_state as u8);
14849 __tmp.put_i8(self.throttle);
14850 __tmp.put_u8(self.airspeed);
14851 __tmp.put_u8(self.airspeed_sp);
14852 __tmp.put_u8(self.groundspeed);
14853 __tmp.put_i8(self.climb_rate);
14854 __tmp.put_u8(self.gps_nsat);
14855 __tmp.put_u8(self.gps_fix_type as u8);
14856 __tmp.put_u8(self.battery_remaining);
14857 __tmp.put_i8(self.temperature);
14858 __tmp.put_i8(self.temperature_air);
14859 __tmp.put_u8(self.failsafe);
14860 __tmp.put_u8(self.wp_num);
14861 if matches!(version, MavlinkVersion::V2) {
14862 let len = __tmp.len();
14863 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14864 } else {
14865 __tmp.len()
14866 }
14867 }
14868}
14869#[doc = "id: 235"]
14870#[doc = "Message appropriate for high latency connections like Iridium (version 2)."]
14871#[derive(Debug, Clone, PartialEq)]
14872#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14873#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14874pub struct HIGH_LATENCY2_DATA {
14875 #[doc = "Timestamp (milliseconds since boot or Unix epoch)"]
14876 pub timestamp: u32,
14877 #[doc = "Latitude"]
14878 pub latitude: i32,
14879 #[doc = "Longitude"]
14880 pub longitude: i32,
14881 #[doc = "A bitfield for use for autopilot-specific flags (2 byte version)."]
14882 pub custom_mode: u16,
14883 #[doc = "Altitude above mean sea level"]
14884 pub altitude: i16,
14885 #[doc = "Altitude setpoint"]
14886 pub target_altitude: i16,
14887 #[doc = "Distance to target waypoint or position"]
14888 pub target_distance: u16,
14889 #[doc = "Current waypoint number"]
14890 pub wp_num: u16,
14891 #[doc = "Bitmap of failure flags."]
14892 pub failure_flags: HlFailureFlag,
14893 #[doc = "Type of the MAV (quadrotor, helicopter, etc.)"]
14894 pub mavtype: MavType,
14895 #[doc = "Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers."]
14896 pub autopilot: MavAutopilot,
14897 #[doc = "Heading"]
14898 pub heading: u8,
14899 #[doc = "Heading setpoint"]
14900 pub target_heading: u8,
14901 #[doc = "Throttle"]
14902 pub throttle: u8,
14903 #[doc = "Airspeed"]
14904 pub airspeed: u8,
14905 #[doc = "Airspeed setpoint"]
14906 pub airspeed_sp: u8,
14907 #[doc = "Groundspeed"]
14908 pub groundspeed: u8,
14909 #[doc = "Windspeed"]
14910 pub windspeed: u8,
14911 #[doc = "Wind heading"]
14912 pub wind_heading: u8,
14913 #[doc = "Maximum error horizontal position since last message"]
14914 pub eph: u8,
14915 #[doc = "Maximum error vertical position since last message"]
14916 pub epv: u8,
14917 #[doc = "Air temperature"]
14918 pub temperature_air: i8,
14919 #[doc = "Maximum climb rate magnitude since last message"]
14920 pub climb_rate: i8,
14921 #[doc = "Battery level (-1 if field not provided)."]
14922 pub battery: i8,
14923 #[doc = "Field for custom payload."]
14924 pub custom0: i8,
14925 #[doc = "Field for custom payload."]
14926 pub custom1: i8,
14927 #[doc = "Field for custom payload."]
14928 pub custom2: i8,
14929}
14930impl HIGH_LATENCY2_DATA {
14931 pub const ENCODED_LEN: usize = 42usize;
14932 pub const DEFAULT: Self = Self {
14933 timestamp: 0_u32,
14934 latitude: 0_i32,
14935 longitude: 0_i32,
14936 custom_mode: 0_u16,
14937 altitude: 0_i16,
14938 target_altitude: 0_i16,
14939 target_distance: 0_u16,
14940 wp_num: 0_u16,
14941 failure_flags: HlFailureFlag::DEFAULT,
14942 mavtype: MavType::DEFAULT,
14943 autopilot: MavAutopilot::DEFAULT,
14944 heading: 0_u8,
14945 target_heading: 0_u8,
14946 throttle: 0_u8,
14947 airspeed: 0_u8,
14948 airspeed_sp: 0_u8,
14949 groundspeed: 0_u8,
14950 windspeed: 0_u8,
14951 wind_heading: 0_u8,
14952 eph: 0_u8,
14953 epv: 0_u8,
14954 temperature_air: 0_i8,
14955 climb_rate: 0_i8,
14956 battery: 0_i8,
14957 custom0: 0_i8,
14958 custom1: 0_i8,
14959 custom2: 0_i8,
14960 };
14961 #[cfg(feature = "arbitrary")]
14962 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14963 use arbitrary::{Arbitrary, Unstructured};
14964 let mut buf = [0u8; 1024];
14965 rng.fill_bytes(&mut buf);
14966 let mut unstructured = Unstructured::new(&buf);
14967 Self::arbitrary(&mut unstructured).unwrap_or_default()
14968 }
14969}
14970impl Default for HIGH_LATENCY2_DATA {
14971 fn default() -> Self {
14972 Self::DEFAULT.clone()
14973 }
14974}
14975impl MessageData for HIGH_LATENCY2_DATA {
14976 type Message = MavMessage;
14977 const ID: u32 = 235u32;
14978 const NAME: &'static str = "HIGH_LATENCY2";
14979 const EXTRA_CRC: u8 = 179u8;
14980 const ENCODED_LEN: usize = 42usize;
14981 fn deser(
14982 _version: MavlinkVersion,
14983 __input: &[u8],
14984 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14985 let avail_len = __input.len();
14986 let mut payload_buf = [0; Self::ENCODED_LEN];
14987 let mut buf = if avail_len < Self::ENCODED_LEN {
14988 payload_buf[0..avail_len].copy_from_slice(__input);
14989 Bytes::new(&payload_buf)
14990 } else {
14991 Bytes::new(__input)
14992 };
14993 let mut __struct = Self::default();
14994 __struct.timestamp = buf.get_u32_le();
14995 __struct.latitude = buf.get_i32_le();
14996 __struct.longitude = buf.get_i32_le();
14997 __struct.custom_mode = buf.get_u16_le();
14998 __struct.altitude = buf.get_i16_le();
14999 __struct.target_altitude = buf.get_i16_le();
15000 __struct.target_distance = buf.get_u16_le();
15001 __struct.wp_num = buf.get_u16_le();
15002 let tmp = buf.get_u16_le();
15003 __struct.failure_flags = HlFailureFlag::from_bits(tmp & HlFailureFlag::all().bits())
15004 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
15005 flag_type: "HlFailureFlag",
15006 value: tmp as u32,
15007 })?;
15008 let tmp = buf.get_u8();
15009 __struct.mavtype =
15010 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
15011 enum_type: "MavType",
15012 value: tmp as u32,
15013 })?;
15014 let tmp = buf.get_u8();
15015 __struct.autopilot =
15016 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
15017 enum_type: "MavAutopilot",
15018 value: tmp as u32,
15019 })?;
15020 __struct.heading = buf.get_u8();
15021 __struct.target_heading = buf.get_u8();
15022 __struct.throttle = buf.get_u8();
15023 __struct.airspeed = buf.get_u8();
15024 __struct.airspeed_sp = buf.get_u8();
15025 __struct.groundspeed = buf.get_u8();
15026 __struct.windspeed = buf.get_u8();
15027 __struct.wind_heading = buf.get_u8();
15028 __struct.eph = buf.get_u8();
15029 __struct.epv = buf.get_u8();
15030 __struct.temperature_air = buf.get_i8();
15031 __struct.climb_rate = buf.get_i8();
15032 __struct.battery = buf.get_i8();
15033 __struct.custom0 = buf.get_i8();
15034 __struct.custom1 = buf.get_i8();
15035 __struct.custom2 = buf.get_i8();
15036 Ok(__struct)
15037 }
15038 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15039 let mut __tmp = BytesMut::new(bytes);
15040 #[allow(clippy::absurd_extreme_comparisons)]
15041 #[allow(unused_comparisons)]
15042 if __tmp.remaining() < Self::ENCODED_LEN {
15043 panic!(
15044 "buffer is too small (need {} bytes, but got {})",
15045 Self::ENCODED_LEN,
15046 __tmp.remaining(),
15047 )
15048 }
15049 __tmp.put_u32_le(self.timestamp);
15050 __tmp.put_i32_le(self.latitude);
15051 __tmp.put_i32_le(self.longitude);
15052 __tmp.put_u16_le(self.custom_mode);
15053 __tmp.put_i16_le(self.altitude);
15054 __tmp.put_i16_le(self.target_altitude);
15055 __tmp.put_u16_le(self.target_distance);
15056 __tmp.put_u16_le(self.wp_num);
15057 __tmp.put_u16_le(self.failure_flags.bits());
15058 __tmp.put_u8(self.mavtype as u8);
15059 __tmp.put_u8(self.autopilot as u8);
15060 __tmp.put_u8(self.heading);
15061 __tmp.put_u8(self.target_heading);
15062 __tmp.put_u8(self.throttle);
15063 __tmp.put_u8(self.airspeed);
15064 __tmp.put_u8(self.airspeed_sp);
15065 __tmp.put_u8(self.groundspeed);
15066 __tmp.put_u8(self.windspeed);
15067 __tmp.put_u8(self.wind_heading);
15068 __tmp.put_u8(self.eph);
15069 __tmp.put_u8(self.epv);
15070 __tmp.put_i8(self.temperature_air);
15071 __tmp.put_i8(self.climb_rate);
15072 __tmp.put_i8(self.battery);
15073 __tmp.put_i8(self.custom0);
15074 __tmp.put_i8(self.custom1);
15075 __tmp.put_i8(self.custom2);
15076 if matches!(version, MavlinkVersion::V2) {
15077 let len = __tmp.len();
15078 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15079 } else {
15080 __tmp.len()
15081 }
15082 }
15083}
15084#[doc = "id: 93"]
15085#[doc = "Sent from autopilot to simulation. Hardware in the loop control outputs. Alternative to HIL_CONTROLS."]
15086#[derive(Debug, Clone, PartialEq)]
15087#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15088#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15089pub struct HIL_ACTUATOR_CONTROLS_DATA {
15090 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
15091 pub time_usec: u64,
15092 #[doc = "Flags bitmask."]
15093 pub flags: HilActuatorControlsFlags,
15094 #[doc = "Control outputs -1 .. 1. Channel assignment depends on the simulated hardware."]
15095 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15096 pub controls: [f32; 16],
15097 #[doc = "System mode. Includes arming state."]
15098 pub mode: MavModeFlag,
15099}
15100impl HIL_ACTUATOR_CONTROLS_DATA {
15101 pub const ENCODED_LEN: usize = 81usize;
15102 pub const DEFAULT: Self = Self {
15103 time_usec: 0_u64,
15104 flags: HilActuatorControlsFlags::DEFAULT,
15105 controls: [0.0_f32; 16usize],
15106 mode: MavModeFlag::DEFAULT,
15107 };
15108 #[cfg(feature = "arbitrary")]
15109 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15110 use arbitrary::{Arbitrary, Unstructured};
15111 let mut buf = [0u8; 1024];
15112 rng.fill_bytes(&mut buf);
15113 let mut unstructured = Unstructured::new(&buf);
15114 Self::arbitrary(&mut unstructured).unwrap_or_default()
15115 }
15116}
15117impl Default for HIL_ACTUATOR_CONTROLS_DATA {
15118 fn default() -> Self {
15119 Self::DEFAULT.clone()
15120 }
15121}
15122impl MessageData for HIL_ACTUATOR_CONTROLS_DATA {
15123 type Message = MavMessage;
15124 const ID: u32 = 93u32;
15125 const NAME: &'static str = "HIL_ACTUATOR_CONTROLS";
15126 const EXTRA_CRC: u8 = 47u8;
15127 const ENCODED_LEN: usize = 81usize;
15128 fn deser(
15129 _version: MavlinkVersion,
15130 __input: &[u8],
15131 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15132 let avail_len = __input.len();
15133 let mut payload_buf = [0; Self::ENCODED_LEN];
15134 let mut buf = if avail_len < Self::ENCODED_LEN {
15135 payload_buf[0..avail_len].copy_from_slice(__input);
15136 Bytes::new(&payload_buf)
15137 } else {
15138 Bytes::new(__input)
15139 };
15140 let mut __struct = Self::default();
15141 __struct.time_usec = buf.get_u64_le();
15142 let tmp = buf.get_u64_le();
15143 __struct.flags =
15144 HilActuatorControlsFlags::from_bits(tmp & HilActuatorControlsFlags::all().bits())
15145 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
15146 flag_type: "HilActuatorControlsFlags",
15147 value: tmp as u32,
15148 })?;
15149 for v in &mut __struct.controls {
15150 let val = buf.get_f32_le();
15151 *v = val;
15152 }
15153 let tmp = buf.get_u8();
15154 __struct.mode = MavModeFlag::from_bits(tmp & MavModeFlag::all().bits()).ok_or(
15155 ::mavlink_core::error::ParserError::InvalidFlag {
15156 flag_type: "MavModeFlag",
15157 value: tmp as u32,
15158 },
15159 )?;
15160 Ok(__struct)
15161 }
15162 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15163 let mut __tmp = BytesMut::new(bytes);
15164 #[allow(clippy::absurd_extreme_comparisons)]
15165 #[allow(unused_comparisons)]
15166 if __tmp.remaining() < Self::ENCODED_LEN {
15167 panic!(
15168 "buffer is too small (need {} bytes, but got {})",
15169 Self::ENCODED_LEN,
15170 __tmp.remaining(),
15171 )
15172 }
15173 __tmp.put_u64_le(self.time_usec);
15174 __tmp.put_u64_le(self.flags.bits());
15175 for val in &self.controls {
15176 __tmp.put_f32_le(*val);
15177 }
15178 __tmp.put_u8(self.mode.bits());
15179 if matches!(version, MavlinkVersion::V2) {
15180 let len = __tmp.len();
15181 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15182 } else {
15183 __tmp.len()
15184 }
15185 }
15186}
15187#[doc = "id: 91"]
15188#[doc = "Sent from autopilot to simulation. Hardware in the loop control outputs. Alternative to HIL_ACTUATOR_CONTROLS."]
15189#[derive(Debug, Clone, PartialEq)]
15190#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15191#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15192pub struct HIL_CONTROLS_DATA {
15193 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
15194 pub time_usec: u64,
15195 #[doc = "Control output -1 .. 1"]
15196 pub roll_ailerons: f32,
15197 #[doc = "Control output -1 .. 1"]
15198 pub pitch_elevator: f32,
15199 #[doc = "Control output -1 .. 1"]
15200 pub yaw_rudder: f32,
15201 #[doc = "Throttle 0 .. 1"]
15202 pub throttle: f32,
15203 #[doc = "Aux 1, -1 .. 1"]
15204 pub aux1: f32,
15205 #[doc = "Aux 2, -1 .. 1"]
15206 pub aux2: f32,
15207 #[doc = "Aux 3, -1 .. 1"]
15208 pub aux3: f32,
15209 #[doc = "Aux 4, -1 .. 1"]
15210 pub aux4: f32,
15211 #[doc = "System mode."]
15212 pub mode: MavMode,
15213 #[doc = "Navigation mode (MAV_NAV_MODE)"]
15214 pub nav_mode: u8,
15215}
15216impl HIL_CONTROLS_DATA {
15217 pub const ENCODED_LEN: usize = 42usize;
15218 pub const DEFAULT: Self = Self {
15219 time_usec: 0_u64,
15220 roll_ailerons: 0.0_f32,
15221 pitch_elevator: 0.0_f32,
15222 yaw_rudder: 0.0_f32,
15223 throttle: 0.0_f32,
15224 aux1: 0.0_f32,
15225 aux2: 0.0_f32,
15226 aux3: 0.0_f32,
15227 aux4: 0.0_f32,
15228 mode: MavMode::DEFAULT,
15229 nav_mode: 0_u8,
15230 };
15231 #[cfg(feature = "arbitrary")]
15232 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15233 use arbitrary::{Arbitrary, Unstructured};
15234 let mut buf = [0u8; 1024];
15235 rng.fill_bytes(&mut buf);
15236 let mut unstructured = Unstructured::new(&buf);
15237 Self::arbitrary(&mut unstructured).unwrap_or_default()
15238 }
15239}
15240impl Default for HIL_CONTROLS_DATA {
15241 fn default() -> Self {
15242 Self::DEFAULT.clone()
15243 }
15244}
15245impl MessageData for HIL_CONTROLS_DATA {
15246 type Message = MavMessage;
15247 const ID: u32 = 91u32;
15248 const NAME: &'static str = "HIL_CONTROLS";
15249 const EXTRA_CRC: u8 = 63u8;
15250 const ENCODED_LEN: usize = 42usize;
15251 fn deser(
15252 _version: MavlinkVersion,
15253 __input: &[u8],
15254 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15255 let avail_len = __input.len();
15256 let mut payload_buf = [0; Self::ENCODED_LEN];
15257 let mut buf = if avail_len < Self::ENCODED_LEN {
15258 payload_buf[0..avail_len].copy_from_slice(__input);
15259 Bytes::new(&payload_buf)
15260 } else {
15261 Bytes::new(__input)
15262 };
15263 let mut __struct = Self::default();
15264 __struct.time_usec = buf.get_u64_le();
15265 __struct.roll_ailerons = buf.get_f32_le();
15266 __struct.pitch_elevator = buf.get_f32_le();
15267 __struct.yaw_rudder = buf.get_f32_le();
15268 __struct.throttle = buf.get_f32_le();
15269 __struct.aux1 = buf.get_f32_le();
15270 __struct.aux2 = buf.get_f32_le();
15271 __struct.aux3 = buf.get_f32_le();
15272 __struct.aux4 = buf.get_f32_le();
15273 let tmp = buf.get_u8();
15274 __struct.mode =
15275 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
15276 enum_type: "MavMode",
15277 value: tmp as u32,
15278 })?;
15279 __struct.nav_mode = buf.get_u8();
15280 Ok(__struct)
15281 }
15282 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15283 let mut __tmp = BytesMut::new(bytes);
15284 #[allow(clippy::absurd_extreme_comparisons)]
15285 #[allow(unused_comparisons)]
15286 if __tmp.remaining() < Self::ENCODED_LEN {
15287 panic!(
15288 "buffer is too small (need {} bytes, but got {})",
15289 Self::ENCODED_LEN,
15290 __tmp.remaining(),
15291 )
15292 }
15293 __tmp.put_u64_le(self.time_usec);
15294 __tmp.put_f32_le(self.roll_ailerons);
15295 __tmp.put_f32_le(self.pitch_elevator);
15296 __tmp.put_f32_le(self.yaw_rudder);
15297 __tmp.put_f32_le(self.throttle);
15298 __tmp.put_f32_le(self.aux1);
15299 __tmp.put_f32_le(self.aux2);
15300 __tmp.put_f32_le(self.aux3);
15301 __tmp.put_f32_le(self.aux4);
15302 __tmp.put_u8(self.mode as u8);
15303 __tmp.put_u8(self.nav_mode);
15304 if matches!(version, MavlinkVersion::V2) {
15305 let len = __tmp.len();
15306 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15307 } else {
15308 __tmp.len()
15309 }
15310 }
15311}
15312#[doc = "id: 113"]
15313#[doc = "The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate."]
15314#[derive(Debug, Clone, PartialEq)]
15315#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15316#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15317pub struct HIL_GPS_DATA {
15318 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
15319 pub time_usec: u64,
15320 #[doc = "Latitude (WGS84)"]
15321 pub lat: i32,
15322 #[doc = "Longitude (WGS84)"]
15323 pub lon: i32,
15324 #[doc = "Altitude (MSL). Positive for up."]
15325 pub alt: i32,
15326 #[doc = "GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
15327 pub eph: u16,
15328 #[doc = "GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
15329 pub epv: u16,
15330 #[doc = "GPS ground speed. If unknown, set to: UINT16_MAX"]
15331 pub vel: u16,
15332 #[doc = "GPS velocity in north direction in earth-fixed NED frame"]
15333 pub vn: i16,
15334 #[doc = "GPS velocity in east direction in earth-fixed NED frame"]
15335 pub ve: i16,
15336 #[doc = "GPS velocity in down direction in earth-fixed NED frame"]
15337 pub vd: i16,
15338 #[doc = "Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
15339 pub cog: u16,
15340 #[doc = "0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix."]
15341 pub fix_type: u8,
15342 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
15343 pub satellites_visible: u8,
15344 #[doc = "GPS ID (zero indexed). Used for multiple GPS inputs"]
15345 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
15346 pub id: u8,
15347 #[doc = "Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north"]
15348 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
15349 pub yaw: u16,
15350}
15351impl HIL_GPS_DATA {
15352 pub const ENCODED_LEN: usize = 39usize;
15353 pub const DEFAULT: Self = Self {
15354 time_usec: 0_u64,
15355 lat: 0_i32,
15356 lon: 0_i32,
15357 alt: 0_i32,
15358 eph: 0_u16,
15359 epv: 0_u16,
15360 vel: 0_u16,
15361 vn: 0_i16,
15362 ve: 0_i16,
15363 vd: 0_i16,
15364 cog: 0_u16,
15365 fix_type: 0_u8,
15366 satellites_visible: 0_u8,
15367 id: 0_u8,
15368 yaw: 0_u16,
15369 };
15370 #[cfg(feature = "arbitrary")]
15371 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15372 use arbitrary::{Arbitrary, Unstructured};
15373 let mut buf = [0u8; 1024];
15374 rng.fill_bytes(&mut buf);
15375 let mut unstructured = Unstructured::new(&buf);
15376 Self::arbitrary(&mut unstructured).unwrap_or_default()
15377 }
15378}
15379impl Default for HIL_GPS_DATA {
15380 fn default() -> Self {
15381 Self::DEFAULT.clone()
15382 }
15383}
15384impl MessageData for HIL_GPS_DATA {
15385 type Message = MavMessage;
15386 const ID: u32 = 113u32;
15387 const NAME: &'static str = "HIL_GPS";
15388 const EXTRA_CRC: u8 = 124u8;
15389 const ENCODED_LEN: usize = 39usize;
15390 fn deser(
15391 _version: MavlinkVersion,
15392 __input: &[u8],
15393 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15394 let avail_len = __input.len();
15395 let mut payload_buf = [0; Self::ENCODED_LEN];
15396 let mut buf = if avail_len < Self::ENCODED_LEN {
15397 payload_buf[0..avail_len].copy_from_slice(__input);
15398 Bytes::new(&payload_buf)
15399 } else {
15400 Bytes::new(__input)
15401 };
15402 let mut __struct = Self::default();
15403 __struct.time_usec = buf.get_u64_le();
15404 __struct.lat = buf.get_i32_le();
15405 __struct.lon = buf.get_i32_le();
15406 __struct.alt = buf.get_i32_le();
15407 __struct.eph = buf.get_u16_le();
15408 __struct.epv = buf.get_u16_le();
15409 __struct.vel = buf.get_u16_le();
15410 __struct.vn = buf.get_i16_le();
15411 __struct.ve = buf.get_i16_le();
15412 __struct.vd = buf.get_i16_le();
15413 __struct.cog = buf.get_u16_le();
15414 __struct.fix_type = buf.get_u8();
15415 __struct.satellites_visible = buf.get_u8();
15416 __struct.id = buf.get_u8();
15417 __struct.yaw = buf.get_u16_le();
15418 Ok(__struct)
15419 }
15420 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15421 let mut __tmp = BytesMut::new(bytes);
15422 #[allow(clippy::absurd_extreme_comparisons)]
15423 #[allow(unused_comparisons)]
15424 if __tmp.remaining() < Self::ENCODED_LEN {
15425 panic!(
15426 "buffer is too small (need {} bytes, but got {})",
15427 Self::ENCODED_LEN,
15428 __tmp.remaining(),
15429 )
15430 }
15431 __tmp.put_u64_le(self.time_usec);
15432 __tmp.put_i32_le(self.lat);
15433 __tmp.put_i32_le(self.lon);
15434 __tmp.put_i32_le(self.alt);
15435 __tmp.put_u16_le(self.eph);
15436 __tmp.put_u16_le(self.epv);
15437 __tmp.put_u16_le(self.vel);
15438 __tmp.put_i16_le(self.vn);
15439 __tmp.put_i16_le(self.ve);
15440 __tmp.put_i16_le(self.vd);
15441 __tmp.put_u16_le(self.cog);
15442 __tmp.put_u8(self.fix_type);
15443 __tmp.put_u8(self.satellites_visible);
15444 __tmp.put_u8(self.id);
15445 __tmp.put_u16_le(self.yaw);
15446 if matches!(version, MavlinkVersion::V2) {
15447 let len = __tmp.len();
15448 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15449 } else {
15450 __tmp.len()
15451 }
15452 }
15453}
15454#[doc = "id: 114"]
15455#[doc = "Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor)."]
15456#[derive(Debug, Clone, PartialEq)]
15457#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15458#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15459pub struct HIL_OPTICAL_FLOW_DATA {
15460 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
15461 pub time_usec: u64,
15462 #[doc = "Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the."]
15463 pub integration_time_us: u32,
15464 #[doc = "Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)"]
15465 pub integrated_x: f32,
15466 #[doc = "Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)"]
15467 pub integrated_y: f32,
15468 #[doc = "RH rotation around X axis"]
15469 pub integrated_xgyro: f32,
15470 #[doc = "RH rotation around Y axis"]
15471 pub integrated_ygyro: f32,
15472 #[doc = "RH rotation around Z axis"]
15473 pub integrated_zgyro: f32,
15474 #[doc = "Time since the distance was sampled."]
15475 pub time_delta_distance_us: u32,
15476 #[doc = "Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance."]
15477 pub distance: f32,
15478 #[doc = "Temperature"]
15479 pub temperature: i16,
15480 #[doc = "Sensor ID"]
15481 pub sensor_id: u8,
15482 #[doc = "Optical flow quality / confidence. 0: no valid flow, 255: maximum quality"]
15483 pub quality: u8,
15484}
15485impl HIL_OPTICAL_FLOW_DATA {
15486 pub const ENCODED_LEN: usize = 44usize;
15487 pub const DEFAULT: Self = Self {
15488 time_usec: 0_u64,
15489 integration_time_us: 0_u32,
15490 integrated_x: 0.0_f32,
15491 integrated_y: 0.0_f32,
15492 integrated_xgyro: 0.0_f32,
15493 integrated_ygyro: 0.0_f32,
15494 integrated_zgyro: 0.0_f32,
15495 time_delta_distance_us: 0_u32,
15496 distance: 0.0_f32,
15497 temperature: 0_i16,
15498 sensor_id: 0_u8,
15499 quality: 0_u8,
15500 };
15501 #[cfg(feature = "arbitrary")]
15502 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15503 use arbitrary::{Arbitrary, Unstructured};
15504 let mut buf = [0u8; 1024];
15505 rng.fill_bytes(&mut buf);
15506 let mut unstructured = Unstructured::new(&buf);
15507 Self::arbitrary(&mut unstructured).unwrap_or_default()
15508 }
15509}
15510impl Default for HIL_OPTICAL_FLOW_DATA {
15511 fn default() -> Self {
15512 Self::DEFAULT.clone()
15513 }
15514}
15515impl MessageData for HIL_OPTICAL_FLOW_DATA {
15516 type Message = MavMessage;
15517 const ID: u32 = 114u32;
15518 const NAME: &'static str = "HIL_OPTICAL_FLOW";
15519 const EXTRA_CRC: u8 = 237u8;
15520 const ENCODED_LEN: usize = 44usize;
15521 fn deser(
15522 _version: MavlinkVersion,
15523 __input: &[u8],
15524 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15525 let avail_len = __input.len();
15526 let mut payload_buf = [0; Self::ENCODED_LEN];
15527 let mut buf = if avail_len < Self::ENCODED_LEN {
15528 payload_buf[0..avail_len].copy_from_slice(__input);
15529 Bytes::new(&payload_buf)
15530 } else {
15531 Bytes::new(__input)
15532 };
15533 let mut __struct = Self::default();
15534 __struct.time_usec = buf.get_u64_le();
15535 __struct.integration_time_us = buf.get_u32_le();
15536 __struct.integrated_x = buf.get_f32_le();
15537 __struct.integrated_y = buf.get_f32_le();
15538 __struct.integrated_xgyro = buf.get_f32_le();
15539 __struct.integrated_ygyro = buf.get_f32_le();
15540 __struct.integrated_zgyro = buf.get_f32_le();
15541 __struct.time_delta_distance_us = buf.get_u32_le();
15542 __struct.distance = buf.get_f32_le();
15543 __struct.temperature = buf.get_i16_le();
15544 __struct.sensor_id = buf.get_u8();
15545 __struct.quality = buf.get_u8();
15546 Ok(__struct)
15547 }
15548 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15549 let mut __tmp = BytesMut::new(bytes);
15550 #[allow(clippy::absurd_extreme_comparisons)]
15551 #[allow(unused_comparisons)]
15552 if __tmp.remaining() < Self::ENCODED_LEN {
15553 panic!(
15554 "buffer is too small (need {} bytes, but got {})",
15555 Self::ENCODED_LEN,
15556 __tmp.remaining(),
15557 )
15558 }
15559 __tmp.put_u64_le(self.time_usec);
15560 __tmp.put_u32_le(self.integration_time_us);
15561 __tmp.put_f32_le(self.integrated_x);
15562 __tmp.put_f32_le(self.integrated_y);
15563 __tmp.put_f32_le(self.integrated_xgyro);
15564 __tmp.put_f32_le(self.integrated_ygyro);
15565 __tmp.put_f32_le(self.integrated_zgyro);
15566 __tmp.put_u32_le(self.time_delta_distance_us);
15567 __tmp.put_f32_le(self.distance);
15568 __tmp.put_i16_le(self.temperature);
15569 __tmp.put_u8(self.sensor_id);
15570 __tmp.put_u8(self.quality);
15571 if matches!(version, MavlinkVersion::V2) {
15572 let len = __tmp.len();
15573 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15574 } else {
15575 __tmp.len()
15576 }
15577 }
15578}
15579#[doc = "id: 92"]
15580#[doc = "Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification."]
15581#[derive(Debug, Clone, PartialEq)]
15582#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15583#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15584pub struct HIL_RC_INPUTS_RAW_DATA {
15585 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
15586 pub time_usec: u64,
15587 #[doc = "RC channel 1 value"]
15588 pub chan1_raw: u16,
15589 #[doc = "RC channel 2 value"]
15590 pub chan2_raw: u16,
15591 #[doc = "RC channel 3 value"]
15592 pub chan3_raw: u16,
15593 #[doc = "RC channel 4 value"]
15594 pub chan4_raw: u16,
15595 #[doc = "RC channel 5 value"]
15596 pub chan5_raw: u16,
15597 #[doc = "RC channel 6 value"]
15598 pub chan6_raw: u16,
15599 #[doc = "RC channel 7 value"]
15600 pub chan7_raw: u16,
15601 #[doc = "RC channel 8 value"]
15602 pub chan8_raw: u16,
15603 #[doc = "RC channel 9 value"]
15604 pub chan9_raw: u16,
15605 #[doc = "RC channel 10 value"]
15606 pub chan10_raw: u16,
15607 #[doc = "RC channel 11 value"]
15608 pub chan11_raw: u16,
15609 #[doc = "RC channel 12 value"]
15610 pub chan12_raw: u16,
15611 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
15612 pub rssi: u8,
15613}
15614impl HIL_RC_INPUTS_RAW_DATA {
15615 pub const ENCODED_LEN: usize = 33usize;
15616 pub const DEFAULT: Self = Self {
15617 time_usec: 0_u64,
15618 chan1_raw: 0_u16,
15619 chan2_raw: 0_u16,
15620 chan3_raw: 0_u16,
15621 chan4_raw: 0_u16,
15622 chan5_raw: 0_u16,
15623 chan6_raw: 0_u16,
15624 chan7_raw: 0_u16,
15625 chan8_raw: 0_u16,
15626 chan9_raw: 0_u16,
15627 chan10_raw: 0_u16,
15628 chan11_raw: 0_u16,
15629 chan12_raw: 0_u16,
15630 rssi: 0_u8,
15631 };
15632 #[cfg(feature = "arbitrary")]
15633 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15634 use arbitrary::{Arbitrary, Unstructured};
15635 let mut buf = [0u8; 1024];
15636 rng.fill_bytes(&mut buf);
15637 let mut unstructured = Unstructured::new(&buf);
15638 Self::arbitrary(&mut unstructured).unwrap_or_default()
15639 }
15640}
15641impl Default for HIL_RC_INPUTS_RAW_DATA {
15642 fn default() -> Self {
15643 Self::DEFAULT.clone()
15644 }
15645}
15646impl MessageData for HIL_RC_INPUTS_RAW_DATA {
15647 type Message = MavMessage;
15648 const ID: u32 = 92u32;
15649 const NAME: &'static str = "HIL_RC_INPUTS_RAW";
15650 const EXTRA_CRC: u8 = 54u8;
15651 const ENCODED_LEN: usize = 33usize;
15652 fn deser(
15653 _version: MavlinkVersion,
15654 __input: &[u8],
15655 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15656 let avail_len = __input.len();
15657 let mut payload_buf = [0; Self::ENCODED_LEN];
15658 let mut buf = if avail_len < Self::ENCODED_LEN {
15659 payload_buf[0..avail_len].copy_from_slice(__input);
15660 Bytes::new(&payload_buf)
15661 } else {
15662 Bytes::new(__input)
15663 };
15664 let mut __struct = Self::default();
15665 __struct.time_usec = buf.get_u64_le();
15666 __struct.chan1_raw = buf.get_u16_le();
15667 __struct.chan2_raw = buf.get_u16_le();
15668 __struct.chan3_raw = buf.get_u16_le();
15669 __struct.chan4_raw = buf.get_u16_le();
15670 __struct.chan5_raw = buf.get_u16_le();
15671 __struct.chan6_raw = buf.get_u16_le();
15672 __struct.chan7_raw = buf.get_u16_le();
15673 __struct.chan8_raw = buf.get_u16_le();
15674 __struct.chan9_raw = buf.get_u16_le();
15675 __struct.chan10_raw = buf.get_u16_le();
15676 __struct.chan11_raw = buf.get_u16_le();
15677 __struct.chan12_raw = buf.get_u16_le();
15678 __struct.rssi = buf.get_u8();
15679 Ok(__struct)
15680 }
15681 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15682 let mut __tmp = BytesMut::new(bytes);
15683 #[allow(clippy::absurd_extreme_comparisons)]
15684 #[allow(unused_comparisons)]
15685 if __tmp.remaining() < Self::ENCODED_LEN {
15686 panic!(
15687 "buffer is too small (need {} bytes, but got {})",
15688 Self::ENCODED_LEN,
15689 __tmp.remaining(),
15690 )
15691 }
15692 __tmp.put_u64_le(self.time_usec);
15693 __tmp.put_u16_le(self.chan1_raw);
15694 __tmp.put_u16_le(self.chan2_raw);
15695 __tmp.put_u16_le(self.chan3_raw);
15696 __tmp.put_u16_le(self.chan4_raw);
15697 __tmp.put_u16_le(self.chan5_raw);
15698 __tmp.put_u16_le(self.chan6_raw);
15699 __tmp.put_u16_le(self.chan7_raw);
15700 __tmp.put_u16_le(self.chan8_raw);
15701 __tmp.put_u16_le(self.chan9_raw);
15702 __tmp.put_u16_le(self.chan10_raw);
15703 __tmp.put_u16_le(self.chan11_raw);
15704 __tmp.put_u16_le(self.chan12_raw);
15705 __tmp.put_u8(self.rssi);
15706 if matches!(version, MavlinkVersion::V2) {
15707 let len = __tmp.len();
15708 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15709 } else {
15710 __tmp.len()
15711 }
15712 }
15713}
15714#[doc = "id: 107"]
15715#[doc = "The IMU readings in SI units in NED body frame."]
15716#[derive(Debug, Clone, PartialEq)]
15717#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15718#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15719pub struct HIL_SENSOR_DATA {
15720 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
15721 pub time_usec: u64,
15722 #[doc = "X acceleration"]
15723 pub xacc: f32,
15724 #[doc = "Y acceleration"]
15725 pub yacc: f32,
15726 #[doc = "Z acceleration"]
15727 pub zacc: f32,
15728 #[doc = "Angular speed around X axis in body frame"]
15729 pub xgyro: f32,
15730 #[doc = "Angular speed around Y axis in body frame"]
15731 pub ygyro: f32,
15732 #[doc = "Angular speed around Z axis in body frame"]
15733 pub zgyro: f32,
15734 #[doc = "X Magnetic field"]
15735 pub xmag: f32,
15736 #[doc = "Y Magnetic field"]
15737 pub ymag: f32,
15738 #[doc = "Z Magnetic field"]
15739 pub zmag: f32,
15740 #[doc = "Absolute pressure"]
15741 pub abs_pressure: f32,
15742 #[doc = "Differential pressure (airspeed)"]
15743 pub diff_pressure: f32,
15744 #[doc = "Altitude calculated from pressure"]
15745 pub pressure_alt: f32,
15746 #[doc = "Temperature"]
15747 pub temperature: f32,
15748 #[doc = "Bitmap for fields that have updated since last message"]
15749 pub fields_updated: HilSensorUpdatedFlags,
15750 #[doc = "Sensor ID (zero indexed). Used for multiple sensor inputs"]
15751 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
15752 pub id: u8,
15753}
15754impl HIL_SENSOR_DATA {
15755 pub const ENCODED_LEN: usize = 65usize;
15756 pub const DEFAULT: Self = Self {
15757 time_usec: 0_u64,
15758 xacc: 0.0_f32,
15759 yacc: 0.0_f32,
15760 zacc: 0.0_f32,
15761 xgyro: 0.0_f32,
15762 ygyro: 0.0_f32,
15763 zgyro: 0.0_f32,
15764 xmag: 0.0_f32,
15765 ymag: 0.0_f32,
15766 zmag: 0.0_f32,
15767 abs_pressure: 0.0_f32,
15768 diff_pressure: 0.0_f32,
15769 pressure_alt: 0.0_f32,
15770 temperature: 0.0_f32,
15771 fields_updated: HilSensorUpdatedFlags::DEFAULT,
15772 id: 0_u8,
15773 };
15774 #[cfg(feature = "arbitrary")]
15775 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15776 use arbitrary::{Arbitrary, Unstructured};
15777 let mut buf = [0u8; 1024];
15778 rng.fill_bytes(&mut buf);
15779 let mut unstructured = Unstructured::new(&buf);
15780 Self::arbitrary(&mut unstructured).unwrap_or_default()
15781 }
15782}
15783impl Default for HIL_SENSOR_DATA {
15784 fn default() -> Self {
15785 Self::DEFAULT.clone()
15786 }
15787}
15788impl MessageData for HIL_SENSOR_DATA {
15789 type Message = MavMessage;
15790 const ID: u32 = 107u32;
15791 const NAME: &'static str = "HIL_SENSOR";
15792 const EXTRA_CRC: u8 = 108u8;
15793 const ENCODED_LEN: usize = 65usize;
15794 fn deser(
15795 _version: MavlinkVersion,
15796 __input: &[u8],
15797 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15798 let avail_len = __input.len();
15799 let mut payload_buf = [0; Self::ENCODED_LEN];
15800 let mut buf = if avail_len < Self::ENCODED_LEN {
15801 payload_buf[0..avail_len].copy_from_slice(__input);
15802 Bytes::new(&payload_buf)
15803 } else {
15804 Bytes::new(__input)
15805 };
15806 let mut __struct = Self::default();
15807 __struct.time_usec = buf.get_u64_le();
15808 __struct.xacc = buf.get_f32_le();
15809 __struct.yacc = buf.get_f32_le();
15810 __struct.zacc = buf.get_f32_le();
15811 __struct.xgyro = buf.get_f32_le();
15812 __struct.ygyro = buf.get_f32_le();
15813 __struct.zgyro = buf.get_f32_le();
15814 __struct.xmag = buf.get_f32_le();
15815 __struct.ymag = buf.get_f32_le();
15816 __struct.zmag = buf.get_f32_le();
15817 __struct.abs_pressure = buf.get_f32_le();
15818 __struct.diff_pressure = buf.get_f32_le();
15819 __struct.pressure_alt = buf.get_f32_le();
15820 __struct.temperature = buf.get_f32_le();
15821 let tmp = buf.get_u32_le();
15822 __struct.fields_updated = HilSensorUpdatedFlags::from_bits(
15823 tmp & HilSensorUpdatedFlags::all().bits(),
15824 )
15825 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
15826 flag_type: "HilSensorUpdatedFlags",
15827 value: tmp as u32,
15828 })?;
15829 __struct.id = buf.get_u8();
15830 Ok(__struct)
15831 }
15832 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15833 let mut __tmp = BytesMut::new(bytes);
15834 #[allow(clippy::absurd_extreme_comparisons)]
15835 #[allow(unused_comparisons)]
15836 if __tmp.remaining() < Self::ENCODED_LEN {
15837 panic!(
15838 "buffer is too small (need {} bytes, but got {})",
15839 Self::ENCODED_LEN,
15840 __tmp.remaining(),
15841 )
15842 }
15843 __tmp.put_u64_le(self.time_usec);
15844 __tmp.put_f32_le(self.xacc);
15845 __tmp.put_f32_le(self.yacc);
15846 __tmp.put_f32_le(self.zacc);
15847 __tmp.put_f32_le(self.xgyro);
15848 __tmp.put_f32_le(self.ygyro);
15849 __tmp.put_f32_le(self.zgyro);
15850 __tmp.put_f32_le(self.xmag);
15851 __tmp.put_f32_le(self.ymag);
15852 __tmp.put_f32_le(self.zmag);
15853 __tmp.put_f32_le(self.abs_pressure);
15854 __tmp.put_f32_le(self.diff_pressure);
15855 __tmp.put_f32_le(self.pressure_alt);
15856 __tmp.put_f32_le(self.temperature);
15857 __tmp.put_u32_le(self.fields_updated.bits());
15858 __tmp.put_u8(self.id);
15859 if matches!(version, MavlinkVersion::V2) {
15860 let len = __tmp.len();
15861 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15862 } else {
15863 __tmp.len()
15864 }
15865 }
15866}
15867#[doc = "id: 90"]
15868#[doc = "Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations."]
15869#[derive(Debug, Clone, PartialEq)]
15870#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15871#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15872pub struct HIL_STATE_DATA {
15873 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
15874 pub time_usec: u64,
15875 #[doc = "Roll angle"]
15876 pub roll: f32,
15877 #[doc = "Pitch angle"]
15878 pub pitch: f32,
15879 #[doc = "Yaw angle"]
15880 pub yaw: f32,
15881 #[doc = "Body frame roll / phi angular speed"]
15882 pub rollspeed: f32,
15883 #[doc = "Body frame pitch / theta angular speed"]
15884 pub pitchspeed: f32,
15885 #[doc = "Body frame yaw / psi angular speed"]
15886 pub yawspeed: f32,
15887 #[doc = "Latitude"]
15888 pub lat: i32,
15889 #[doc = "Longitude"]
15890 pub lon: i32,
15891 #[doc = "Altitude"]
15892 pub alt: i32,
15893 #[doc = "Ground X Speed (Latitude)"]
15894 pub vx: i16,
15895 #[doc = "Ground Y Speed (Longitude)"]
15896 pub vy: i16,
15897 #[doc = "Ground Z Speed (Altitude)"]
15898 pub vz: i16,
15899 #[doc = "X acceleration"]
15900 pub xacc: i16,
15901 #[doc = "Y acceleration"]
15902 pub yacc: i16,
15903 #[doc = "Z acceleration"]
15904 pub zacc: i16,
15905}
15906impl HIL_STATE_DATA {
15907 pub const ENCODED_LEN: usize = 56usize;
15908 pub const DEFAULT: Self = Self {
15909 time_usec: 0_u64,
15910 roll: 0.0_f32,
15911 pitch: 0.0_f32,
15912 yaw: 0.0_f32,
15913 rollspeed: 0.0_f32,
15914 pitchspeed: 0.0_f32,
15915 yawspeed: 0.0_f32,
15916 lat: 0_i32,
15917 lon: 0_i32,
15918 alt: 0_i32,
15919 vx: 0_i16,
15920 vy: 0_i16,
15921 vz: 0_i16,
15922 xacc: 0_i16,
15923 yacc: 0_i16,
15924 zacc: 0_i16,
15925 };
15926 #[cfg(feature = "arbitrary")]
15927 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15928 use arbitrary::{Arbitrary, Unstructured};
15929 let mut buf = [0u8; 1024];
15930 rng.fill_bytes(&mut buf);
15931 let mut unstructured = Unstructured::new(&buf);
15932 Self::arbitrary(&mut unstructured).unwrap_or_default()
15933 }
15934}
15935impl Default for HIL_STATE_DATA {
15936 fn default() -> Self {
15937 Self::DEFAULT.clone()
15938 }
15939}
15940impl MessageData for HIL_STATE_DATA {
15941 type Message = MavMessage;
15942 const ID: u32 = 90u32;
15943 const NAME: &'static str = "HIL_STATE";
15944 const EXTRA_CRC: u8 = 183u8;
15945 const ENCODED_LEN: usize = 56usize;
15946 fn deser(
15947 _version: MavlinkVersion,
15948 __input: &[u8],
15949 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15950 let avail_len = __input.len();
15951 let mut payload_buf = [0; Self::ENCODED_LEN];
15952 let mut buf = if avail_len < Self::ENCODED_LEN {
15953 payload_buf[0..avail_len].copy_from_slice(__input);
15954 Bytes::new(&payload_buf)
15955 } else {
15956 Bytes::new(__input)
15957 };
15958 let mut __struct = Self::default();
15959 __struct.time_usec = buf.get_u64_le();
15960 __struct.roll = buf.get_f32_le();
15961 __struct.pitch = buf.get_f32_le();
15962 __struct.yaw = buf.get_f32_le();
15963 __struct.rollspeed = buf.get_f32_le();
15964 __struct.pitchspeed = buf.get_f32_le();
15965 __struct.yawspeed = buf.get_f32_le();
15966 __struct.lat = buf.get_i32_le();
15967 __struct.lon = buf.get_i32_le();
15968 __struct.alt = buf.get_i32_le();
15969 __struct.vx = buf.get_i16_le();
15970 __struct.vy = buf.get_i16_le();
15971 __struct.vz = buf.get_i16_le();
15972 __struct.xacc = buf.get_i16_le();
15973 __struct.yacc = buf.get_i16_le();
15974 __struct.zacc = buf.get_i16_le();
15975 Ok(__struct)
15976 }
15977 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15978 let mut __tmp = BytesMut::new(bytes);
15979 #[allow(clippy::absurd_extreme_comparisons)]
15980 #[allow(unused_comparisons)]
15981 if __tmp.remaining() < Self::ENCODED_LEN {
15982 panic!(
15983 "buffer is too small (need {} bytes, but got {})",
15984 Self::ENCODED_LEN,
15985 __tmp.remaining(),
15986 )
15987 }
15988 __tmp.put_u64_le(self.time_usec);
15989 __tmp.put_f32_le(self.roll);
15990 __tmp.put_f32_le(self.pitch);
15991 __tmp.put_f32_le(self.yaw);
15992 __tmp.put_f32_le(self.rollspeed);
15993 __tmp.put_f32_le(self.pitchspeed);
15994 __tmp.put_f32_le(self.yawspeed);
15995 __tmp.put_i32_le(self.lat);
15996 __tmp.put_i32_le(self.lon);
15997 __tmp.put_i32_le(self.alt);
15998 __tmp.put_i16_le(self.vx);
15999 __tmp.put_i16_le(self.vy);
16000 __tmp.put_i16_le(self.vz);
16001 __tmp.put_i16_le(self.xacc);
16002 __tmp.put_i16_le(self.yacc);
16003 __tmp.put_i16_le(self.zacc);
16004 if matches!(version, MavlinkVersion::V2) {
16005 let len = __tmp.len();
16006 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16007 } else {
16008 __tmp.len()
16009 }
16010 }
16011}
16012#[doc = "id: 115"]
16013#[doc = "Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations."]
16014#[derive(Debug, Clone, PartialEq)]
16015#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16016#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16017pub struct HIL_STATE_QUATERNION_DATA {
16018 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
16019 pub time_usec: u64,
16020 #[doc = "Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)"]
16021 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16022 pub attitude_quaternion: [f32; 4],
16023 #[doc = "Body frame roll / phi angular speed"]
16024 pub rollspeed: f32,
16025 #[doc = "Body frame pitch / theta angular speed"]
16026 pub pitchspeed: f32,
16027 #[doc = "Body frame yaw / psi angular speed"]
16028 pub yawspeed: f32,
16029 #[doc = "Latitude"]
16030 pub lat: i32,
16031 #[doc = "Longitude"]
16032 pub lon: i32,
16033 #[doc = "Altitude"]
16034 pub alt: i32,
16035 #[doc = "Ground X Speed (Latitude)"]
16036 pub vx: i16,
16037 #[doc = "Ground Y Speed (Longitude)"]
16038 pub vy: i16,
16039 #[doc = "Ground Z Speed (Altitude)"]
16040 pub vz: i16,
16041 #[doc = "Indicated airspeed"]
16042 pub ind_airspeed: u16,
16043 #[doc = "True airspeed"]
16044 pub true_airspeed: u16,
16045 #[doc = "X acceleration"]
16046 pub xacc: i16,
16047 #[doc = "Y acceleration"]
16048 pub yacc: i16,
16049 #[doc = "Z acceleration"]
16050 pub zacc: i16,
16051}
16052impl HIL_STATE_QUATERNION_DATA {
16053 pub const ENCODED_LEN: usize = 64usize;
16054 pub const DEFAULT: Self = Self {
16055 time_usec: 0_u64,
16056 attitude_quaternion: [0.0_f32; 4usize],
16057 rollspeed: 0.0_f32,
16058 pitchspeed: 0.0_f32,
16059 yawspeed: 0.0_f32,
16060 lat: 0_i32,
16061 lon: 0_i32,
16062 alt: 0_i32,
16063 vx: 0_i16,
16064 vy: 0_i16,
16065 vz: 0_i16,
16066 ind_airspeed: 0_u16,
16067 true_airspeed: 0_u16,
16068 xacc: 0_i16,
16069 yacc: 0_i16,
16070 zacc: 0_i16,
16071 };
16072 #[cfg(feature = "arbitrary")]
16073 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16074 use arbitrary::{Arbitrary, Unstructured};
16075 let mut buf = [0u8; 1024];
16076 rng.fill_bytes(&mut buf);
16077 let mut unstructured = Unstructured::new(&buf);
16078 Self::arbitrary(&mut unstructured).unwrap_or_default()
16079 }
16080}
16081impl Default for HIL_STATE_QUATERNION_DATA {
16082 fn default() -> Self {
16083 Self::DEFAULT.clone()
16084 }
16085}
16086impl MessageData for HIL_STATE_QUATERNION_DATA {
16087 type Message = MavMessage;
16088 const ID: u32 = 115u32;
16089 const NAME: &'static str = "HIL_STATE_QUATERNION";
16090 const EXTRA_CRC: u8 = 4u8;
16091 const ENCODED_LEN: usize = 64usize;
16092 fn deser(
16093 _version: MavlinkVersion,
16094 __input: &[u8],
16095 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16096 let avail_len = __input.len();
16097 let mut payload_buf = [0; Self::ENCODED_LEN];
16098 let mut buf = if avail_len < Self::ENCODED_LEN {
16099 payload_buf[0..avail_len].copy_from_slice(__input);
16100 Bytes::new(&payload_buf)
16101 } else {
16102 Bytes::new(__input)
16103 };
16104 let mut __struct = Self::default();
16105 __struct.time_usec = buf.get_u64_le();
16106 for v in &mut __struct.attitude_quaternion {
16107 let val = buf.get_f32_le();
16108 *v = val;
16109 }
16110 __struct.rollspeed = buf.get_f32_le();
16111 __struct.pitchspeed = buf.get_f32_le();
16112 __struct.yawspeed = buf.get_f32_le();
16113 __struct.lat = buf.get_i32_le();
16114 __struct.lon = buf.get_i32_le();
16115 __struct.alt = buf.get_i32_le();
16116 __struct.vx = buf.get_i16_le();
16117 __struct.vy = buf.get_i16_le();
16118 __struct.vz = buf.get_i16_le();
16119 __struct.ind_airspeed = buf.get_u16_le();
16120 __struct.true_airspeed = buf.get_u16_le();
16121 __struct.xacc = buf.get_i16_le();
16122 __struct.yacc = buf.get_i16_le();
16123 __struct.zacc = buf.get_i16_le();
16124 Ok(__struct)
16125 }
16126 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16127 let mut __tmp = BytesMut::new(bytes);
16128 #[allow(clippy::absurd_extreme_comparisons)]
16129 #[allow(unused_comparisons)]
16130 if __tmp.remaining() < Self::ENCODED_LEN {
16131 panic!(
16132 "buffer is too small (need {} bytes, but got {})",
16133 Self::ENCODED_LEN,
16134 __tmp.remaining(),
16135 )
16136 }
16137 __tmp.put_u64_le(self.time_usec);
16138 for val in &self.attitude_quaternion {
16139 __tmp.put_f32_le(*val);
16140 }
16141 __tmp.put_f32_le(self.rollspeed);
16142 __tmp.put_f32_le(self.pitchspeed);
16143 __tmp.put_f32_le(self.yawspeed);
16144 __tmp.put_i32_le(self.lat);
16145 __tmp.put_i32_le(self.lon);
16146 __tmp.put_i32_le(self.alt);
16147 __tmp.put_i16_le(self.vx);
16148 __tmp.put_i16_le(self.vy);
16149 __tmp.put_i16_le(self.vz);
16150 __tmp.put_u16_le(self.ind_airspeed);
16151 __tmp.put_u16_le(self.true_airspeed);
16152 __tmp.put_i16_le(self.xacc);
16153 __tmp.put_i16_le(self.yacc);
16154 __tmp.put_i16_le(self.zacc);
16155 if matches!(version, MavlinkVersion::V2) {
16156 let len = __tmp.len();
16157 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16158 } else {
16159 __tmp.len()
16160 }
16161 }
16162}
16163#[doc = "id: 242"]
16164#[doc = "Contains the home position. \tThe home position is the default position that the system will return to and land on. \tThe position must be set automatically by the system during the takeoff, and may also be explicitly set using MAV_CMD_DO_SET_HOME. \tThe global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. \tUnder normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. \tThe approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. Note: this message can be requested by sending the MAV_CMD_REQUEST_MESSAGE with param1=242 (or the deprecated MAV_CMD_GET_HOME_POSITION command)."]
16165#[derive(Debug, Clone, PartialEq)]
16166#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16167#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16168pub struct HOME_POSITION_DATA {
16169 #[doc = "Latitude (WGS84)"]
16170 pub latitude: i32,
16171 #[doc = "Longitude (WGS84)"]
16172 pub longitude: i32,
16173 #[doc = "Altitude (MSL). Positive for up."]
16174 pub altitude: i32,
16175 #[doc = "Local X position of this position in the local coordinate frame (NED)"]
16176 pub x: f32,
16177 #[doc = "Local Y position of this position in the local coordinate frame (NED)"]
16178 pub y: f32,
16179 #[doc = "Local Z position of this position in the local coordinate frame (NED: positive \"down\")"]
16180 pub z: f32,
16181 #[doc = "Quaternion indicating world-to-surface-normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground. All fields should be set to NaN if an accurate quaternion for both heading and surface slope cannot be supplied."]
16182 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16183 pub q: [f32; 4],
16184 #[doc = "Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
16185 pub approach_x: f32,
16186 #[doc = "Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
16187 pub approach_y: f32,
16188 #[doc = "Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
16189 pub approach_z: f32,
16190 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
16191 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16192 pub time_usec: u64,
16193}
16194impl HOME_POSITION_DATA {
16195 pub const ENCODED_LEN: usize = 60usize;
16196 pub const DEFAULT: Self = Self {
16197 latitude: 0_i32,
16198 longitude: 0_i32,
16199 altitude: 0_i32,
16200 x: 0.0_f32,
16201 y: 0.0_f32,
16202 z: 0.0_f32,
16203 q: [0.0_f32; 4usize],
16204 approach_x: 0.0_f32,
16205 approach_y: 0.0_f32,
16206 approach_z: 0.0_f32,
16207 time_usec: 0_u64,
16208 };
16209 #[cfg(feature = "arbitrary")]
16210 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16211 use arbitrary::{Arbitrary, Unstructured};
16212 let mut buf = [0u8; 1024];
16213 rng.fill_bytes(&mut buf);
16214 let mut unstructured = Unstructured::new(&buf);
16215 Self::arbitrary(&mut unstructured).unwrap_or_default()
16216 }
16217}
16218impl Default for HOME_POSITION_DATA {
16219 fn default() -> Self {
16220 Self::DEFAULT.clone()
16221 }
16222}
16223impl MessageData for HOME_POSITION_DATA {
16224 type Message = MavMessage;
16225 const ID: u32 = 242u32;
16226 const NAME: &'static str = "HOME_POSITION";
16227 const EXTRA_CRC: u8 = 104u8;
16228 const ENCODED_LEN: usize = 60usize;
16229 fn deser(
16230 _version: MavlinkVersion,
16231 __input: &[u8],
16232 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16233 let avail_len = __input.len();
16234 let mut payload_buf = [0; Self::ENCODED_LEN];
16235 let mut buf = if avail_len < Self::ENCODED_LEN {
16236 payload_buf[0..avail_len].copy_from_slice(__input);
16237 Bytes::new(&payload_buf)
16238 } else {
16239 Bytes::new(__input)
16240 };
16241 let mut __struct = Self::default();
16242 __struct.latitude = buf.get_i32_le();
16243 __struct.longitude = buf.get_i32_le();
16244 __struct.altitude = buf.get_i32_le();
16245 __struct.x = buf.get_f32_le();
16246 __struct.y = buf.get_f32_le();
16247 __struct.z = buf.get_f32_le();
16248 for v in &mut __struct.q {
16249 let val = buf.get_f32_le();
16250 *v = val;
16251 }
16252 __struct.approach_x = buf.get_f32_le();
16253 __struct.approach_y = buf.get_f32_le();
16254 __struct.approach_z = buf.get_f32_le();
16255 __struct.time_usec = buf.get_u64_le();
16256 Ok(__struct)
16257 }
16258 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16259 let mut __tmp = BytesMut::new(bytes);
16260 #[allow(clippy::absurd_extreme_comparisons)]
16261 #[allow(unused_comparisons)]
16262 if __tmp.remaining() < Self::ENCODED_LEN {
16263 panic!(
16264 "buffer is too small (need {} bytes, but got {})",
16265 Self::ENCODED_LEN,
16266 __tmp.remaining(),
16267 )
16268 }
16269 __tmp.put_i32_le(self.latitude);
16270 __tmp.put_i32_le(self.longitude);
16271 __tmp.put_i32_le(self.altitude);
16272 __tmp.put_f32_le(self.x);
16273 __tmp.put_f32_le(self.y);
16274 __tmp.put_f32_le(self.z);
16275 for val in &self.q {
16276 __tmp.put_f32_le(*val);
16277 }
16278 __tmp.put_f32_le(self.approach_x);
16279 __tmp.put_f32_le(self.approach_y);
16280 __tmp.put_f32_le(self.approach_z);
16281 __tmp.put_u64_le(self.time_usec);
16282 if matches!(version, MavlinkVersion::V2) {
16283 let len = __tmp.len();
16284 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16285 } else {
16286 __tmp.len()
16287 }
16288 }
16289}
16290#[doc = "id: 12920"]
16291#[doc = "Temperature and humidity from hygrometer."]
16292#[derive(Debug, Clone, PartialEq)]
16293#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16294#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16295pub struct HYGROMETER_SENSOR_DATA {
16296 #[doc = "Temperature"]
16297 pub temperature: i16,
16298 #[doc = "Humidity"]
16299 pub humidity: u16,
16300 #[doc = "Hygrometer ID"]
16301 pub id: u8,
16302}
16303impl HYGROMETER_SENSOR_DATA {
16304 pub const ENCODED_LEN: usize = 5usize;
16305 pub const DEFAULT: Self = Self {
16306 temperature: 0_i16,
16307 humidity: 0_u16,
16308 id: 0_u8,
16309 };
16310 #[cfg(feature = "arbitrary")]
16311 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16312 use arbitrary::{Arbitrary, Unstructured};
16313 let mut buf = [0u8; 1024];
16314 rng.fill_bytes(&mut buf);
16315 let mut unstructured = Unstructured::new(&buf);
16316 Self::arbitrary(&mut unstructured).unwrap_or_default()
16317 }
16318}
16319impl Default for HYGROMETER_SENSOR_DATA {
16320 fn default() -> Self {
16321 Self::DEFAULT.clone()
16322 }
16323}
16324impl MessageData for HYGROMETER_SENSOR_DATA {
16325 type Message = MavMessage;
16326 const ID: u32 = 12920u32;
16327 const NAME: &'static str = "HYGROMETER_SENSOR";
16328 const EXTRA_CRC: u8 = 20u8;
16329 const ENCODED_LEN: usize = 5usize;
16330 fn deser(
16331 _version: MavlinkVersion,
16332 __input: &[u8],
16333 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16334 let avail_len = __input.len();
16335 let mut payload_buf = [0; Self::ENCODED_LEN];
16336 let mut buf = if avail_len < Self::ENCODED_LEN {
16337 payload_buf[0..avail_len].copy_from_slice(__input);
16338 Bytes::new(&payload_buf)
16339 } else {
16340 Bytes::new(__input)
16341 };
16342 let mut __struct = Self::default();
16343 __struct.temperature = buf.get_i16_le();
16344 __struct.humidity = buf.get_u16_le();
16345 __struct.id = buf.get_u8();
16346 Ok(__struct)
16347 }
16348 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16349 let mut __tmp = BytesMut::new(bytes);
16350 #[allow(clippy::absurd_extreme_comparisons)]
16351 #[allow(unused_comparisons)]
16352 if __tmp.remaining() < Self::ENCODED_LEN {
16353 panic!(
16354 "buffer is too small (need {} bytes, but got {})",
16355 Self::ENCODED_LEN,
16356 __tmp.remaining(),
16357 )
16358 }
16359 __tmp.put_i16_le(self.temperature);
16360 __tmp.put_u16_le(self.humidity);
16361 __tmp.put_u8(self.id);
16362 if matches!(version, MavlinkVersion::V2) {
16363 let len = __tmp.len();
16364 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16365 } else {
16366 __tmp.len()
16367 }
16368 }
16369}
16370#[doc = "id: 440"]
16371#[doc = "Illuminator status."]
16372#[derive(Debug, Clone, PartialEq)]
16373#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16374#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16375pub struct ILLUMINATOR_STATUS_DATA {
16376 #[doc = "Time since the start-up of the illuminator in ms"]
16377 pub uptime_ms: u32,
16378 #[doc = "Errors"]
16379 pub error_status: IlluminatorErrorFlags,
16380 #[doc = "Illuminator brightness"]
16381 pub brightness: f32,
16382 #[doc = "Illuminator strobing period in seconds"]
16383 pub strobe_period: f32,
16384 #[doc = "Illuminator strobing duty cycle"]
16385 pub strobe_duty_cycle: f32,
16386 #[doc = "Temperature in Celsius"]
16387 pub temp_c: f32,
16388 #[doc = "Minimum strobing period in seconds"]
16389 pub min_strobe_period: f32,
16390 #[doc = "Maximum strobing period in seconds"]
16391 pub max_strobe_period: f32,
16392 #[doc = "0: Illuminators OFF, 1: Illuminators ON"]
16393 pub enable: u8,
16394 #[doc = "Supported illuminator modes"]
16395 pub mode_bitmask: IlluminatorMode,
16396 #[doc = "Illuminator mode"]
16397 pub mode: IlluminatorMode,
16398}
16399impl ILLUMINATOR_STATUS_DATA {
16400 pub const ENCODED_LEN: usize = 35usize;
16401 pub const DEFAULT: Self = Self {
16402 uptime_ms: 0_u32,
16403 error_status: IlluminatorErrorFlags::DEFAULT,
16404 brightness: 0.0_f32,
16405 strobe_period: 0.0_f32,
16406 strobe_duty_cycle: 0.0_f32,
16407 temp_c: 0.0_f32,
16408 min_strobe_period: 0.0_f32,
16409 max_strobe_period: 0.0_f32,
16410 enable: 0_u8,
16411 mode_bitmask: IlluminatorMode::DEFAULT,
16412 mode: IlluminatorMode::DEFAULT,
16413 };
16414 #[cfg(feature = "arbitrary")]
16415 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16416 use arbitrary::{Arbitrary, Unstructured};
16417 let mut buf = [0u8; 1024];
16418 rng.fill_bytes(&mut buf);
16419 let mut unstructured = Unstructured::new(&buf);
16420 Self::arbitrary(&mut unstructured).unwrap_or_default()
16421 }
16422}
16423impl Default for ILLUMINATOR_STATUS_DATA {
16424 fn default() -> Self {
16425 Self::DEFAULT.clone()
16426 }
16427}
16428impl MessageData for ILLUMINATOR_STATUS_DATA {
16429 type Message = MavMessage;
16430 const ID: u32 = 440u32;
16431 const NAME: &'static str = "ILLUMINATOR_STATUS";
16432 const EXTRA_CRC: u8 = 66u8;
16433 const ENCODED_LEN: usize = 35usize;
16434 fn deser(
16435 _version: MavlinkVersion,
16436 __input: &[u8],
16437 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16438 let avail_len = __input.len();
16439 let mut payload_buf = [0; Self::ENCODED_LEN];
16440 let mut buf = if avail_len < Self::ENCODED_LEN {
16441 payload_buf[0..avail_len].copy_from_slice(__input);
16442 Bytes::new(&payload_buf)
16443 } else {
16444 Bytes::new(__input)
16445 };
16446 let mut __struct = Self::default();
16447 __struct.uptime_ms = buf.get_u32_le();
16448 let tmp = buf.get_u32_le();
16449 __struct.error_status = IlluminatorErrorFlags::from_bits(
16450 tmp & IlluminatorErrorFlags::all().bits(),
16451 )
16452 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
16453 flag_type: "IlluminatorErrorFlags",
16454 value: tmp as u32,
16455 })?;
16456 __struct.brightness = buf.get_f32_le();
16457 __struct.strobe_period = buf.get_f32_le();
16458 __struct.strobe_duty_cycle = buf.get_f32_le();
16459 __struct.temp_c = buf.get_f32_le();
16460 __struct.min_strobe_period = buf.get_f32_le();
16461 __struct.max_strobe_period = buf.get_f32_le();
16462 __struct.enable = buf.get_u8();
16463 let tmp = buf.get_u8();
16464 __struct.mode_bitmask =
16465 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16466 enum_type: "IlluminatorMode",
16467 value: tmp as u32,
16468 })?;
16469 let tmp = buf.get_u8();
16470 __struct.mode =
16471 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16472 enum_type: "IlluminatorMode",
16473 value: tmp as u32,
16474 })?;
16475 Ok(__struct)
16476 }
16477 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16478 let mut __tmp = BytesMut::new(bytes);
16479 #[allow(clippy::absurd_extreme_comparisons)]
16480 #[allow(unused_comparisons)]
16481 if __tmp.remaining() < Self::ENCODED_LEN {
16482 panic!(
16483 "buffer is too small (need {} bytes, but got {})",
16484 Self::ENCODED_LEN,
16485 __tmp.remaining(),
16486 )
16487 }
16488 __tmp.put_u32_le(self.uptime_ms);
16489 __tmp.put_u32_le(self.error_status.bits());
16490 __tmp.put_f32_le(self.brightness);
16491 __tmp.put_f32_le(self.strobe_period);
16492 __tmp.put_f32_le(self.strobe_duty_cycle);
16493 __tmp.put_f32_le(self.temp_c);
16494 __tmp.put_f32_le(self.min_strobe_period);
16495 __tmp.put_f32_le(self.max_strobe_period);
16496 __tmp.put_u8(self.enable);
16497 __tmp.put_u8(self.mode_bitmask as u8);
16498 __tmp.put_u8(self.mode as u8);
16499 if matches!(version, MavlinkVersion::V2) {
16500 let len = __tmp.len();
16501 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16502 } else {
16503 __tmp.len()
16504 }
16505 }
16506}
16507#[doc = "id: 335"]
16508#[doc = "Status of the Iridium SBD link."]
16509#[derive(Debug, Clone, PartialEq)]
16510#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16511#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16512pub struct ISBD_LINK_STATUS_DATA {
16513 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
16514 pub timestamp: u64,
16515 #[doc = "Timestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
16516 pub last_heartbeat: u64,
16517 #[doc = "Number of failed SBD sessions."]
16518 pub failed_sessions: u16,
16519 #[doc = "Number of successful SBD sessions."]
16520 pub successful_sessions: u16,
16521 #[doc = "Signal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength."]
16522 pub signal_quality: u8,
16523 #[doc = "1: Ring call pending, 0: No call pending."]
16524 pub ring_pending: u8,
16525 #[doc = "1: Transmission session pending, 0: No transmission session pending."]
16526 pub tx_session_pending: u8,
16527 #[doc = "1: Receiving session pending, 0: No receiving session pending."]
16528 pub rx_session_pending: u8,
16529}
16530impl ISBD_LINK_STATUS_DATA {
16531 pub const ENCODED_LEN: usize = 24usize;
16532 pub const DEFAULT: Self = Self {
16533 timestamp: 0_u64,
16534 last_heartbeat: 0_u64,
16535 failed_sessions: 0_u16,
16536 successful_sessions: 0_u16,
16537 signal_quality: 0_u8,
16538 ring_pending: 0_u8,
16539 tx_session_pending: 0_u8,
16540 rx_session_pending: 0_u8,
16541 };
16542 #[cfg(feature = "arbitrary")]
16543 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16544 use arbitrary::{Arbitrary, Unstructured};
16545 let mut buf = [0u8; 1024];
16546 rng.fill_bytes(&mut buf);
16547 let mut unstructured = Unstructured::new(&buf);
16548 Self::arbitrary(&mut unstructured).unwrap_or_default()
16549 }
16550}
16551impl Default for ISBD_LINK_STATUS_DATA {
16552 fn default() -> Self {
16553 Self::DEFAULT.clone()
16554 }
16555}
16556impl MessageData for ISBD_LINK_STATUS_DATA {
16557 type Message = MavMessage;
16558 const ID: u32 = 335u32;
16559 const NAME: &'static str = "ISBD_LINK_STATUS";
16560 const EXTRA_CRC: u8 = 225u8;
16561 const ENCODED_LEN: usize = 24usize;
16562 fn deser(
16563 _version: MavlinkVersion,
16564 __input: &[u8],
16565 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16566 let avail_len = __input.len();
16567 let mut payload_buf = [0; Self::ENCODED_LEN];
16568 let mut buf = if avail_len < Self::ENCODED_LEN {
16569 payload_buf[0..avail_len].copy_from_slice(__input);
16570 Bytes::new(&payload_buf)
16571 } else {
16572 Bytes::new(__input)
16573 };
16574 let mut __struct = Self::default();
16575 __struct.timestamp = buf.get_u64_le();
16576 __struct.last_heartbeat = buf.get_u64_le();
16577 __struct.failed_sessions = buf.get_u16_le();
16578 __struct.successful_sessions = buf.get_u16_le();
16579 __struct.signal_quality = buf.get_u8();
16580 __struct.ring_pending = buf.get_u8();
16581 __struct.tx_session_pending = buf.get_u8();
16582 __struct.rx_session_pending = buf.get_u8();
16583 Ok(__struct)
16584 }
16585 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16586 let mut __tmp = BytesMut::new(bytes);
16587 #[allow(clippy::absurd_extreme_comparisons)]
16588 #[allow(unused_comparisons)]
16589 if __tmp.remaining() < Self::ENCODED_LEN {
16590 panic!(
16591 "buffer is too small (need {} bytes, but got {})",
16592 Self::ENCODED_LEN,
16593 __tmp.remaining(),
16594 )
16595 }
16596 __tmp.put_u64_le(self.timestamp);
16597 __tmp.put_u64_le(self.last_heartbeat);
16598 __tmp.put_u16_le(self.failed_sessions);
16599 __tmp.put_u16_le(self.successful_sessions);
16600 __tmp.put_u8(self.signal_quality);
16601 __tmp.put_u8(self.ring_pending);
16602 __tmp.put_u8(self.tx_session_pending);
16603 __tmp.put_u8(self.rx_session_pending);
16604 if matches!(version, MavlinkVersion::V2) {
16605 let len = __tmp.len();
16606 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16607 } else {
16608 __tmp.len()
16609 }
16610 }
16611}
16612#[doc = "id: 149"]
16613#[doc = "The location of a landing target. See: <https://mavlink.io/en/services/landing_target.html>."]
16614#[derive(Debug, Clone, PartialEq)]
16615#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16616#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16617pub struct LANDING_TARGET_DATA {
16618 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
16619 pub time_usec: u64,
16620 #[doc = "X-axis angular offset of the target from the center of the image"]
16621 pub angle_x: f32,
16622 #[doc = "Y-axis angular offset of the target from the center of the image"]
16623 pub angle_y: f32,
16624 #[doc = "Distance to the target from the vehicle"]
16625 pub distance: f32,
16626 #[doc = "Size of target along x-axis"]
16627 pub size_x: f32,
16628 #[doc = "Size of target along y-axis"]
16629 pub size_y: f32,
16630 #[doc = "The ID of the target if multiple targets are present"]
16631 pub target_num: u8,
16632 #[doc = "Coordinate frame used for following fields."]
16633 pub frame: MavFrame,
16634 #[doc = "X Position of the landing target in MAV_FRAME"]
16635 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16636 pub x: f32,
16637 #[doc = "Y Position of the landing target in MAV_FRAME"]
16638 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16639 pub y: f32,
16640 #[doc = "Z Position of the landing target in MAV_FRAME"]
16641 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16642 pub z: f32,
16643 #[doc = "Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
16644 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16645 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16646 pub q: [f32; 4],
16647 #[doc = "Type of landing target"]
16648 #[cfg_attr(feature = "serde", serde(default))]
16649 pub mavtype: LandingTargetType,
16650 #[doc = "Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid)."]
16651 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16652 pub position_valid: u8,
16653}
16654impl LANDING_TARGET_DATA {
16655 pub const ENCODED_LEN: usize = 60usize;
16656 pub const DEFAULT: Self = Self {
16657 time_usec: 0_u64,
16658 angle_x: 0.0_f32,
16659 angle_y: 0.0_f32,
16660 distance: 0.0_f32,
16661 size_x: 0.0_f32,
16662 size_y: 0.0_f32,
16663 target_num: 0_u8,
16664 frame: MavFrame::DEFAULT,
16665 x: 0.0_f32,
16666 y: 0.0_f32,
16667 z: 0.0_f32,
16668 q: [0.0_f32; 4usize],
16669 mavtype: LandingTargetType::DEFAULT,
16670 position_valid: 0_u8,
16671 };
16672 #[cfg(feature = "arbitrary")]
16673 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16674 use arbitrary::{Arbitrary, Unstructured};
16675 let mut buf = [0u8; 1024];
16676 rng.fill_bytes(&mut buf);
16677 let mut unstructured = Unstructured::new(&buf);
16678 Self::arbitrary(&mut unstructured).unwrap_or_default()
16679 }
16680}
16681impl Default for LANDING_TARGET_DATA {
16682 fn default() -> Self {
16683 Self::DEFAULT.clone()
16684 }
16685}
16686impl MessageData for LANDING_TARGET_DATA {
16687 type Message = MavMessage;
16688 const ID: u32 = 149u32;
16689 const NAME: &'static str = "LANDING_TARGET";
16690 const EXTRA_CRC: u8 = 200u8;
16691 const ENCODED_LEN: usize = 60usize;
16692 fn deser(
16693 _version: MavlinkVersion,
16694 __input: &[u8],
16695 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16696 let avail_len = __input.len();
16697 let mut payload_buf = [0; Self::ENCODED_LEN];
16698 let mut buf = if avail_len < Self::ENCODED_LEN {
16699 payload_buf[0..avail_len].copy_from_slice(__input);
16700 Bytes::new(&payload_buf)
16701 } else {
16702 Bytes::new(__input)
16703 };
16704 let mut __struct = Self::default();
16705 __struct.time_usec = buf.get_u64_le();
16706 __struct.angle_x = buf.get_f32_le();
16707 __struct.angle_y = buf.get_f32_le();
16708 __struct.distance = buf.get_f32_le();
16709 __struct.size_x = buf.get_f32_le();
16710 __struct.size_y = buf.get_f32_le();
16711 __struct.target_num = buf.get_u8();
16712 let tmp = buf.get_u8();
16713 __struct.frame =
16714 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16715 enum_type: "MavFrame",
16716 value: tmp as u32,
16717 })?;
16718 __struct.x = buf.get_f32_le();
16719 __struct.y = buf.get_f32_le();
16720 __struct.z = buf.get_f32_le();
16721 for v in &mut __struct.q {
16722 let val = buf.get_f32_le();
16723 *v = val;
16724 }
16725 let tmp = buf.get_u8();
16726 __struct.mavtype =
16727 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16728 enum_type: "LandingTargetType",
16729 value: tmp as u32,
16730 })?;
16731 __struct.position_valid = buf.get_u8();
16732 Ok(__struct)
16733 }
16734 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16735 let mut __tmp = BytesMut::new(bytes);
16736 #[allow(clippy::absurd_extreme_comparisons)]
16737 #[allow(unused_comparisons)]
16738 if __tmp.remaining() < Self::ENCODED_LEN {
16739 panic!(
16740 "buffer is too small (need {} bytes, but got {})",
16741 Self::ENCODED_LEN,
16742 __tmp.remaining(),
16743 )
16744 }
16745 __tmp.put_u64_le(self.time_usec);
16746 __tmp.put_f32_le(self.angle_x);
16747 __tmp.put_f32_le(self.angle_y);
16748 __tmp.put_f32_le(self.distance);
16749 __tmp.put_f32_le(self.size_x);
16750 __tmp.put_f32_le(self.size_y);
16751 __tmp.put_u8(self.target_num);
16752 __tmp.put_u8(self.frame as u8);
16753 __tmp.put_f32_le(self.x);
16754 __tmp.put_f32_le(self.y);
16755 __tmp.put_f32_le(self.z);
16756 for val in &self.q {
16757 __tmp.put_f32_le(*val);
16758 }
16759 __tmp.put_u8(self.mavtype as u8);
16760 __tmp.put_u8(self.position_valid);
16761 if matches!(version, MavlinkVersion::V2) {
16762 let len = __tmp.len();
16763 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16764 } else {
16765 __tmp.len()
16766 }
16767 }
16768}
16769#[doc = "id: 8"]
16770#[doc = "Status generated in each node in the communication chain and injected into MAVLink stream."]
16771#[derive(Debug, Clone, PartialEq)]
16772#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16773#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16774pub struct LINK_NODE_STATUS_DATA {
16775 #[doc = "Timestamp (time since system boot)."]
16776 pub timestamp: u64,
16777 #[doc = "Transmit rate"]
16778 pub tx_rate: u32,
16779 #[doc = "Receive rate"]
16780 pub rx_rate: u32,
16781 #[doc = "Messages sent"]
16782 pub messages_sent: u32,
16783 #[doc = "Messages received (estimated from counting seq)"]
16784 pub messages_received: u32,
16785 #[doc = "Messages lost (estimated from counting seq)"]
16786 pub messages_lost: u32,
16787 #[doc = "Number of bytes that could not be parsed correctly."]
16788 pub rx_parse_err: u16,
16789 #[doc = "Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX"]
16790 pub tx_overflows: u16,
16791 #[doc = "Receive buffer overflows. This number wraps around as it reaches UINT16_MAX"]
16792 pub rx_overflows: u16,
16793 #[doc = "Remaining free transmit buffer space"]
16794 pub tx_buf: u8,
16795 #[doc = "Remaining free receive buffer space"]
16796 pub rx_buf: u8,
16797}
16798impl LINK_NODE_STATUS_DATA {
16799 pub const ENCODED_LEN: usize = 36usize;
16800 pub const DEFAULT: Self = Self {
16801 timestamp: 0_u64,
16802 tx_rate: 0_u32,
16803 rx_rate: 0_u32,
16804 messages_sent: 0_u32,
16805 messages_received: 0_u32,
16806 messages_lost: 0_u32,
16807 rx_parse_err: 0_u16,
16808 tx_overflows: 0_u16,
16809 rx_overflows: 0_u16,
16810 tx_buf: 0_u8,
16811 rx_buf: 0_u8,
16812 };
16813 #[cfg(feature = "arbitrary")]
16814 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16815 use arbitrary::{Arbitrary, Unstructured};
16816 let mut buf = [0u8; 1024];
16817 rng.fill_bytes(&mut buf);
16818 let mut unstructured = Unstructured::new(&buf);
16819 Self::arbitrary(&mut unstructured).unwrap_or_default()
16820 }
16821}
16822impl Default for LINK_NODE_STATUS_DATA {
16823 fn default() -> Self {
16824 Self::DEFAULT.clone()
16825 }
16826}
16827impl MessageData for LINK_NODE_STATUS_DATA {
16828 type Message = MavMessage;
16829 const ID: u32 = 8u32;
16830 const NAME: &'static str = "LINK_NODE_STATUS";
16831 const EXTRA_CRC: u8 = 117u8;
16832 const ENCODED_LEN: usize = 36usize;
16833 fn deser(
16834 _version: MavlinkVersion,
16835 __input: &[u8],
16836 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16837 let avail_len = __input.len();
16838 let mut payload_buf = [0; Self::ENCODED_LEN];
16839 let mut buf = if avail_len < Self::ENCODED_LEN {
16840 payload_buf[0..avail_len].copy_from_slice(__input);
16841 Bytes::new(&payload_buf)
16842 } else {
16843 Bytes::new(__input)
16844 };
16845 let mut __struct = Self::default();
16846 __struct.timestamp = buf.get_u64_le();
16847 __struct.tx_rate = buf.get_u32_le();
16848 __struct.rx_rate = buf.get_u32_le();
16849 __struct.messages_sent = buf.get_u32_le();
16850 __struct.messages_received = buf.get_u32_le();
16851 __struct.messages_lost = buf.get_u32_le();
16852 __struct.rx_parse_err = buf.get_u16_le();
16853 __struct.tx_overflows = buf.get_u16_le();
16854 __struct.rx_overflows = buf.get_u16_le();
16855 __struct.tx_buf = buf.get_u8();
16856 __struct.rx_buf = buf.get_u8();
16857 Ok(__struct)
16858 }
16859 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16860 let mut __tmp = BytesMut::new(bytes);
16861 #[allow(clippy::absurd_extreme_comparisons)]
16862 #[allow(unused_comparisons)]
16863 if __tmp.remaining() < Self::ENCODED_LEN {
16864 panic!(
16865 "buffer is too small (need {} bytes, but got {})",
16866 Self::ENCODED_LEN,
16867 __tmp.remaining(),
16868 )
16869 }
16870 __tmp.put_u64_le(self.timestamp);
16871 __tmp.put_u32_le(self.tx_rate);
16872 __tmp.put_u32_le(self.rx_rate);
16873 __tmp.put_u32_le(self.messages_sent);
16874 __tmp.put_u32_le(self.messages_received);
16875 __tmp.put_u32_le(self.messages_lost);
16876 __tmp.put_u16_le(self.rx_parse_err);
16877 __tmp.put_u16_le(self.tx_overflows);
16878 __tmp.put_u16_le(self.rx_overflows);
16879 __tmp.put_u8(self.tx_buf);
16880 __tmp.put_u8(self.rx_buf);
16881 if matches!(version, MavlinkVersion::V2) {
16882 let len = __tmp.len();
16883 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16884 } else {
16885 __tmp.len()
16886 }
16887 }
16888}
16889#[doc = "id: 32"]
16890#[doc = "The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
16891#[derive(Debug, Clone, PartialEq)]
16892#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16893#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16894pub struct LOCAL_POSITION_NED_DATA {
16895 #[doc = "Timestamp (time since system boot)."]
16896 pub time_boot_ms: u32,
16897 #[doc = "X Position"]
16898 pub x: f32,
16899 #[doc = "Y Position"]
16900 pub y: f32,
16901 #[doc = "Z Position"]
16902 pub z: f32,
16903 #[doc = "X Speed"]
16904 pub vx: f32,
16905 #[doc = "Y Speed"]
16906 pub vy: f32,
16907 #[doc = "Z Speed"]
16908 pub vz: f32,
16909}
16910impl LOCAL_POSITION_NED_DATA {
16911 pub const ENCODED_LEN: usize = 28usize;
16912 pub const DEFAULT: Self = Self {
16913 time_boot_ms: 0_u32,
16914 x: 0.0_f32,
16915 y: 0.0_f32,
16916 z: 0.0_f32,
16917 vx: 0.0_f32,
16918 vy: 0.0_f32,
16919 vz: 0.0_f32,
16920 };
16921 #[cfg(feature = "arbitrary")]
16922 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16923 use arbitrary::{Arbitrary, Unstructured};
16924 let mut buf = [0u8; 1024];
16925 rng.fill_bytes(&mut buf);
16926 let mut unstructured = Unstructured::new(&buf);
16927 Self::arbitrary(&mut unstructured).unwrap_or_default()
16928 }
16929}
16930impl Default for LOCAL_POSITION_NED_DATA {
16931 fn default() -> Self {
16932 Self::DEFAULT.clone()
16933 }
16934}
16935impl MessageData for LOCAL_POSITION_NED_DATA {
16936 type Message = MavMessage;
16937 const ID: u32 = 32u32;
16938 const NAME: &'static str = "LOCAL_POSITION_NED";
16939 const EXTRA_CRC: u8 = 185u8;
16940 const ENCODED_LEN: usize = 28usize;
16941 fn deser(
16942 _version: MavlinkVersion,
16943 __input: &[u8],
16944 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16945 let avail_len = __input.len();
16946 let mut payload_buf = [0; Self::ENCODED_LEN];
16947 let mut buf = if avail_len < Self::ENCODED_LEN {
16948 payload_buf[0..avail_len].copy_from_slice(__input);
16949 Bytes::new(&payload_buf)
16950 } else {
16951 Bytes::new(__input)
16952 };
16953 let mut __struct = Self::default();
16954 __struct.time_boot_ms = buf.get_u32_le();
16955 __struct.x = buf.get_f32_le();
16956 __struct.y = buf.get_f32_le();
16957 __struct.z = buf.get_f32_le();
16958 __struct.vx = buf.get_f32_le();
16959 __struct.vy = buf.get_f32_le();
16960 __struct.vz = buf.get_f32_le();
16961 Ok(__struct)
16962 }
16963 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16964 let mut __tmp = BytesMut::new(bytes);
16965 #[allow(clippy::absurd_extreme_comparisons)]
16966 #[allow(unused_comparisons)]
16967 if __tmp.remaining() < Self::ENCODED_LEN {
16968 panic!(
16969 "buffer is too small (need {} bytes, but got {})",
16970 Self::ENCODED_LEN,
16971 __tmp.remaining(),
16972 )
16973 }
16974 __tmp.put_u32_le(self.time_boot_ms);
16975 __tmp.put_f32_le(self.x);
16976 __tmp.put_f32_le(self.y);
16977 __tmp.put_f32_le(self.z);
16978 __tmp.put_f32_le(self.vx);
16979 __tmp.put_f32_le(self.vy);
16980 __tmp.put_f32_le(self.vz);
16981 if matches!(version, MavlinkVersion::V2) {
16982 let len = __tmp.len();
16983 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16984 } else {
16985 __tmp.len()
16986 }
16987 }
16988}
16989#[doc = "id: 64"]
16990#[doc = "The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
16991#[derive(Debug, Clone, PartialEq)]
16992#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16993#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16994pub struct LOCAL_POSITION_NED_COV_DATA {
16995 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
16996 pub time_usec: u64,
16997 #[doc = "X Position"]
16998 pub x: f32,
16999 #[doc = "Y Position"]
17000 pub y: f32,
17001 #[doc = "Z Position"]
17002 pub z: f32,
17003 #[doc = "X Speed"]
17004 pub vx: f32,
17005 #[doc = "Y Speed"]
17006 pub vy: f32,
17007 #[doc = "Z Speed"]
17008 pub vz: f32,
17009 #[doc = "X Acceleration"]
17010 pub ax: f32,
17011 #[doc = "Y Acceleration"]
17012 pub ay: f32,
17013 #[doc = "Z Acceleration"]
17014 pub az: f32,
17015 #[doc = "Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array."]
17016 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17017 pub covariance: [f32; 45],
17018 #[doc = "Class id of the estimator this estimate originated from."]
17019 pub estimator_type: MavEstimatorType,
17020}
17021impl LOCAL_POSITION_NED_COV_DATA {
17022 pub const ENCODED_LEN: usize = 225usize;
17023 pub const DEFAULT: Self = Self {
17024 time_usec: 0_u64,
17025 x: 0.0_f32,
17026 y: 0.0_f32,
17027 z: 0.0_f32,
17028 vx: 0.0_f32,
17029 vy: 0.0_f32,
17030 vz: 0.0_f32,
17031 ax: 0.0_f32,
17032 ay: 0.0_f32,
17033 az: 0.0_f32,
17034 covariance: [0.0_f32; 45usize],
17035 estimator_type: MavEstimatorType::DEFAULT,
17036 };
17037 #[cfg(feature = "arbitrary")]
17038 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17039 use arbitrary::{Arbitrary, Unstructured};
17040 let mut buf = [0u8; 1024];
17041 rng.fill_bytes(&mut buf);
17042 let mut unstructured = Unstructured::new(&buf);
17043 Self::arbitrary(&mut unstructured).unwrap_or_default()
17044 }
17045}
17046impl Default for LOCAL_POSITION_NED_COV_DATA {
17047 fn default() -> Self {
17048 Self::DEFAULT.clone()
17049 }
17050}
17051impl MessageData for LOCAL_POSITION_NED_COV_DATA {
17052 type Message = MavMessage;
17053 const ID: u32 = 64u32;
17054 const NAME: &'static str = "LOCAL_POSITION_NED_COV";
17055 const EXTRA_CRC: u8 = 191u8;
17056 const ENCODED_LEN: usize = 225usize;
17057 fn deser(
17058 _version: MavlinkVersion,
17059 __input: &[u8],
17060 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17061 let avail_len = __input.len();
17062 let mut payload_buf = [0; Self::ENCODED_LEN];
17063 let mut buf = if avail_len < Self::ENCODED_LEN {
17064 payload_buf[0..avail_len].copy_from_slice(__input);
17065 Bytes::new(&payload_buf)
17066 } else {
17067 Bytes::new(__input)
17068 };
17069 let mut __struct = Self::default();
17070 __struct.time_usec = buf.get_u64_le();
17071 __struct.x = buf.get_f32_le();
17072 __struct.y = buf.get_f32_le();
17073 __struct.z = buf.get_f32_le();
17074 __struct.vx = buf.get_f32_le();
17075 __struct.vy = buf.get_f32_le();
17076 __struct.vz = buf.get_f32_le();
17077 __struct.ax = buf.get_f32_le();
17078 __struct.ay = buf.get_f32_le();
17079 __struct.az = buf.get_f32_le();
17080 for v in &mut __struct.covariance {
17081 let val = buf.get_f32_le();
17082 *v = val;
17083 }
17084 let tmp = buf.get_u8();
17085 __struct.estimator_type =
17086 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
17087 enum_type: "MavEstimatorType",
17088 value: tmp as u32,
17089 })?;
17090 Ok(__struct)
17091 }
17092 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17093 let mut __tmp = BytesMut::new(bytes);
17094 #[allow(clippy::absurd_extreme_comparisons)]
17095 #[allow(unused_comparisons)]
17096 if __tmp.remaining() < Self::ENCODED_LEN {
17097 panic!(
17098 "buffer is too small (need {} bytes, but got {})",
17099 Self::ENCODED_LEN,
17100 __tmp.remaining(),
17101 )
17102 }
17103 __tmp.put_u64_le(self.time_usec);
17104 __tmp.put_f32_le(self.x);
17105 __tmp.put_f32_le(self.y);
17106 __tmp.put_f32_le(self.z);
17107 __tmp.put_f32_le(self.vx);
17108 __tmp.put_f32_le(self.vy);
17109 __tmp.put_f32_le(self.vz);
17110 __tmp.put_f32_le(self.ax);
17111 __tmp.put_f32_le(self.ay);
17112 __tmp.put_f32_le(self.az);
17113 for val in &self.covariance {
17114 __tmp.put_f32_le(*val);
17115 }
17116 __tmp.put_u8(self.estimator_type as u8);
17117 if matches!(version, MavlinkVersion::V2) {
17118 let len = __tmp.len();
17119 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17120 } else {
17121 __tmp.len()
17122 }
17123 }
17124}
17125#[doc = "id: 89"]
17126#[doc = "The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
17127#[derive(Debug, Clone, PartialEq)]
17128#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17129#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17130pub struct LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
17131 #[doc = "Timestamp (time since system boot)."]
17132 pub time_boot_ms: u32,
17133 #[doc = "X Position"]
17134 pub x: f32,
17135 #[doc = "Y Position"]
17136 pub y: f32,
17137 #[doc = "Z Position"]
17138 pub z: f32,
17139 #[doc = "Roll"]
17140 pub roll: f32,
17141 #[doc = "Pitch"]
17142 pub pitch: f32,
17143 #[doc = "Yaw"]
17144 pub yaw: f32,
17145}
17146impl LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
17147 pub const ENCODED_LEN: usize = 28usize;
17148 pub const DEFAULT: Self = Self {
17149 time_boot_ms: 0_u32,
17150 x: 0.0_f32,
17151 y: 0.0_f32,
17152 z: 0.0_f32,
17153 roll: 0.0_f32,
17154 pitch: 0.0_f32,
17155 yaw: 0.0_f32,
17156 };
17157 #[cfg(feature = "arbitrary")]
17158 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17159 use arbitrary::{Arbitrary, Unstructured};
17160 let mut buf = [0u8; 1024];
17161 rng.fill_bytes(&mut buf);
17162 let mut unstructured = Unstructured::new(&buf);
17163 Self::arbitrary(&mut unstructured).unwrap_or_default()
17164 }
17165}
17166impl Default for LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
17167 fn default() -> Self {
17168 Self::DEFAULT.clone()
17169 }
17170}
17171impl MessageData for LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
17172 type Message = MavMessage;
17173 const ID: u32 = 89u32;
17174 const NAME: &'static str = "LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET";
17175 const EXTRA_CRC: u8 = 231u8;
17176 const ENCODED_LEN: usize = 28usize;
17177 fn deser(
17178 _version: MavlinkVersion,
17179 __input: &[u8],
17180 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17181 let avail_len = __input.len();
17182 let mut payload_buf = [0; Self::ENCODED_LEN];
17183 let mut buf = if avail_len < Self::ENCODED_LEN {
17184 payload_buf[0..avail_len].copy_from_slice(__input);
17185 Bytes::new(&payload_buf)
17186 } else {
17187 Bytes::new(__input)
17188 };
17189 let mut __struct = Self::default();
17190 __struct.time_boot_ms = buf.get_u32_le();
17191 __struct.x = buf.get_f32_le();
17192 __struct.y = buf.get_f32_le();
17193 __struct.z = buf.get_f32_le();
17194 __struct.roll = buf.get_f32_le();
17195 __struct.pitch = buf.get_f32_le();
17196 __struct.yaw = buf.get_f32_le();
17197 Ok(__struct)
17198 }
17199 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17200 let mut __tmp = BytesMut::new(bytes);
17201 #[allow(clippy::absurd_extreme_comparisons)]
17202 #[allow(unused_comparisons)]
17203 if __tmp.remaining() < Self::ENCODED_LEN {
17204 panic!(
17205 "buffer is too small (need {} bytes, but got {})",
17206 Self::ENCODED_LEN,
17207 __tmp.remaining(),
17208 )
17209 }
17210 __tmp.put_u32_le(self.time_boot_ms);
17211 __tmp.put_f32_le(self.x);
17212 __tmp.put_f32_le(self.y);
17213 __tmp.put_f32_le(self.z);
17214 __tmp.put_f32_le(self.roll);
17215 __tmp.put_f32_le(self.pitch);
17216 __tmp.put_f32_le(self.yaw);
17217 if matches!(version, MavlinkVersion::V2) {
17218 let len = __tmp.len();
17219 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17220 } else {
17221 __tmp.len()
17222 }
17223 }
17224}
17225#[doc = "id: 268"]
17226#[doc = "An ack for a LOGGING_DATA_ACKED message."]
17227#[derive(Debug, Clone, PartialEq)]
17228#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17229#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17230pub struct LOGGING_ACK_DATA {
17231 #[doc = "sequence number (must match the one in LOGGING_DATA_ACKED)"]
17232 pub sequence: u16,
17233 #[doc = "system ID of the target"]
17234 pub target_system: u8,
17235 #[doc = "component ID of the target"]
17236 pub target_component: u8,
17237}
17238impl LOGGING_ACK_DATA {
17239 pub const ENCODED_LEN: usize = 4usize;
17240 pub const DEFAULT: Self = Self {
17241 sequence: 0_u16,
17242 target_system: 0_u8,
17243 target_component: 0_u8,
17244 };
17245 #[cfg(feature = "arbitrary")]
17246 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17247 use arbitrary::{Arbitrary, Unstructured};
17248 let mut buf = [0u8; 1024];
17249 rng.fill_bytes(&mut buf);
17250 let mut unstructured = Unstructured::new(&buf);
17251 Self::arbitrary(&mut unstructured).unwrap_or_default()
17252 }
17253}
17254impl Default for LOGGING_ACK_DATA {
17255 fn default() -> Self {
17256 Self::DEFAULT.clone()
17257 }
17258}
17259impl MessageData for LOGGING_ACK_DATA {
17260 type Message = MavMessage;
17261 const ID: u32 = 268u32;
17262 const NAME: &'static str = "LOGGING_ACK";
17263 const EXTRA_CRC: u8 = 14u8;
17264 const ENCODED_LEN: usize = 4usize;
17265 fn deser(
17266 _version: MavlinkVersion,
17267 __input: &[u8],
17268 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17269 let avail_len = __input.len();
17270 let mut payload_buf = [0; Self::ENCODED_LEN];
17271 let mut buf = if avail_len < Self::ENCODED_LEN {
17272 payload_buf[0..avail_len].copy_from_slice(__input);
17273 Bytes::new(&payload_buf)
17274 } else {
17275 Bytes::new(__input)
17276 };
17277 let mut __struct = Self::default();
17278 __struct.sequence = buf.get_u16_le();
17279 __struct.target_system = buf.get_u8();
17280 __struct.target_component = buf.get_u8();
17281 Ok(__struct)
17282 }
17283 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17284 let mut __tmp = BytesMut::new(bytes);
17285 #[allow(clippy::absurd_extreme_comparisons)]
17286 #[allow(unused_comparisons)]
17287 if __tmp.remaining() < Self::ENCODED_LEN {
17288 panic!(
17289 "buffer is too small (need {} bytes, but got {})",
17290 Self::ENCODED_LEN,
17291 __tmp.remaining(),
17292 )
17293 }
17294 __tmp.put_u16_le(self.sequence);
17295 __tmp.put_u8(self.target_system);
17296 __tmp.put_u8(self.target_component);
17297 if matches!(version, MavlinkVersion::V2) {
17298 let len = __tmp.len();
17299 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17300 } else {
17301 __tmp.len()
17302 }
17303 }
17304}
17305#[doc = "id: 266"]
17306#[doc = "A message containing logged data (see also MAV_CMD_LOGGING_START)."]
17307#[derive(Debug, Clone, PartialEq)]
17308#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17309#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17310pub struct LOGGING_DATA_DATA {
17311 #[doc = "sequence number (can wrap)"]
17312 pub sequence: u16,
17313 #[doc = "system ID of the target"]
17314 pub target_system: u8,
17315 #[doc = "component ID of the target"]
17316 pub target_component: u8,
17317 #[doc = "data length"]
17318 pub length: u8,
17319 #[doc = "offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists)."]
17320 pub first_message_offset: u8,
17321 #[doc = "logged data"]
17322 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17323 pub data: [u8; 249],
17324}
17325impl LOGGING_DATA_DATA {
17326 pub const ENCODED_LEN: usize = 255usize;
17327 pub const DEFAULT: Self = Self {
17328 sequence: 0_u16,
17329 target_system: 0_u8,
17330 target_component: 0_u8,
17331 length: 0_u8,
17332 first_message_offset: 0_u8,
17333 data: [0_u8; 249usize],
17334 };
17335 #[cfg(feature = "arbitrary")]
17336 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17337 use arbitrary::{Arbitrary, Unstructured};
17338 let mut buf = [0u8; 1024];
17339 rng.fill_bytes(&mut buf);
17340 let mut unstructured = Unstructured::new(&buf);
17341 Self::arbitrary(&mut unstructured).unwrap_or_default()
17342 }
17343}
17344impl Default for LOGGING_DATA_DATA {
17345 fn default() -> Self {
17346 Self::DEFAULT.clone()
17347 }
17348}
17349impl MessageData for LOGGING_DATA_DATA {
17350 type Message = MavMessage;
17351 const ID: u32 = 266u32;
17352 const NAME: &'static str = "LOGGING_DATA";
17353 const EXTRA_CRC: u8 = 193u8;
17354 const ENCODED_LEN: usize = 255usize;
17355 fn deser(
17356 _version: MavlinkVersion,
17357 __input: &[u8],
17358 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17359 let avail_len = __input.len();
17360 let mut payload_buf = [0; Self::ENCODED_LEN];
17361 let mut buf = if avail_len < Self::ENCODED_LEN {
17362 payload_buf[0..avail_len].copy_from_slice(__input);
17363 Bytes::new(&payload_buf)
17364 } else {
17365 Bytes::new(__input)
17366 };
17367 let mut __struct = Self::default();
17368 __struct.sequence = buf.get_u16_le();
17369 __struct.target_system = buf.get_u8();
17370 __struct.target_component = buf.get_u8();
17371 __struct.length = buf.get_u8();
17372 __struct.first_message_offset = buf.get_u8();
17373 for v in &mut __struct.data {
17374 let val = buf.get_u8();
17375 *v = val;
17376 }
17377 Ok(__struct)
17378 }
17379 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17380 let mut __tmp = BytesMut::new(bytes);
17381 #[allow(clippy::absurd_extreme_comparisons)]
17382 #[allow(unused_comparisons)]
17383 if __tmp.remaining() < Self::ENCODED_LEN {
17384 panic!(
17385 "buffer is too small (need {} bytes, but got {})",
17386 Self::ENCODED_LEN,
17387 __tmp.remaining(),
17388 )
17389 }
17390 __tmp.put_u16_le(self.sequence);
17391 __tmp.put_u8(self.target_system);
17392 __tmp.put_u8(self.target_component);
17393 __tmp.put_u8(self.length);
17394 __tmp.put_u8(self.first_message_offset);
17395 for val in &self.data {
17396 __tmp.put_u8(*val);
17397 }
17398 if matches!(version, MavlinkVersion::V2) {
17399 let len = __tmp.len();
17400 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17401 } else {
17402 __tmp.len()
17403 }
17404 }
17405}
17406#[doc = "id: 267"]
17407#[doc = "A message containing logged data which requires a LOGGING_ACK to be sent back."]
17408#[derive(Debug, Clone, PartialEq)]
17409#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17410#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17411pub struct LOGGING_DATA_ACKED_DATA {
17412 #[doc = "sequence number (can wrap)"]
17413 pub sequence: u16,
17414 #[doc = "system ID of the target"]
17415 pub target_system: u8,
17416 #[doc = "component ID of the target"]
17417 pub target_component: u8,
17418 #[doc = "data length"]
17419 pub length: u8,
17420 #[doc = "offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists)."]
17421 pub first_message_offset: u8,
17422 #[doc = "logged data"]
17423 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17424 pub data: [u8; 249],
17425}
17426impl LOGGING_DATA_ACKED_DATA {
17427 pub const ENCODED_LEN: usize = 255usize;
17428 pub const DEFAULT: Self = Self {
17429 sequence: 0_u16,
17430 target_system: 0_u8,
17431 target_component: 0_u8,
17432 length: 0_u8,
17433 first_message_offset: 0_u8,
17434 data: [0_u8; 249usize],
17435 };
17436 #[cfg(feature = "arbitrary")]
17437 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17438 use arbitrary::{Arbitrary, Unstructured};
17439 let mut buf = [0u8; 1024];
17440 rng.fill_bytes(&mut buf);
17441 let mut unstructured = Unstructured::new(&buf);
17442 Self::arbitrary(&mut unstructured).unwrap_or_default()
17443 }
17444}
17445impl Default for LOGGING_DATA_ACKED_DATA {
17446 fn default() -> Self {
17447 Self::DEFAULT.clone()
17448 }
17449}
17450impl MessageData for LOGGING_DATA_ACKED_DATA {
17451 type Message = MavMessage;
17452 const ID: u32 = 267u32;
17453 const NAME: &'static str = "LOGGING_DATA_ACKED";
17454 const EXTRA_CRC: u8 = 35u8;
17455 const ENCODED_LEN: usize = 255usize;
17456 fn deser(
17457 _version: MavlinkVersion,
17458 __input: &[u8],
17459 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17460 let avail_len = __input.len();
17461 let mut payload_buf = [0; Self::ENCODED_LEN];
17462 let mut buf = if avail_len < Self::ENCODED_LEN {
17463 payload_buf[0..avail_len].copy_from_slice(__input);
17464 Bytes::new(&payload_buf)
17465 } else {
17466 Bytes::new(__input)
17467 };
17468 let mut __struct = Self::default();
17469 __struct.sequence = buf.get_u16_le();
17470 __struct.target_system = buf.get_u8();
17471 __struct.target_component = buf.get_u8();
17472 __struct.length = buf.get_u8();
17473 __struct.first_message_offset = buf.get_u8();
17474 for v in &mut __struct.data {
17475 let val = buf.get_u8();
17476 *v = val;
17477 }
17478 Ok(__struct)
17479 }
17480 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17481 let mut __tmp = BytesMut::new(bytes);
17482 #[allow(clippy::absurd_extreme_comparisons)]
17483 #[allow(unused_comparisons)]
17484 if __tmp.remaining() < Self::ENCODED_LEN {
17485 panic!(
17486 "buffer is too small (need {} bytes, but got {})",
17487 Self::ENCODED_LEN,
17488 __tmp.remaining(),
17489 )
17490 }
17491 __tmp.put_u16_le(self.sequence);
17492 __tmp.put_u8(self.target_system);
17493 __tmp.put_u8(self.target_component);
17494 __tmp.put_u8(self.length);
17495 __tmp.put_u8(self.first_message_offset);
17496 for val in &self.data {
17497 __tmp.put_u8(*val);
17498 }
17499 if matches!(version, MavlinkVersion::V2) {
17500 let len = __tmp.len();
17501 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17502 } else {
17503 __tmp.len()
17504 }
17505 }
17506}
17507#[doc = "id: 120"]
17508#[doc = "Reply to LOG_REQUEST_DATA."]
17509#[derive(Debug, Clone, PartialEq)]
17510#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17511#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17512pub struct LOG_DATA_DATA {
17513 #[doc = "Offset into the log"]
17514 pub ofs: u32,
17515 #[doc = "Log id (from LOG_ENTRY reply)"]
17516 pub id: u16,
17517 #[doc = "Number of bytes (zero for end of log)"]
17518 pub count: u8,
17519 #[doc = "log data"]
17520 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17521 pub data: [u8; 90],
17522}
17523impl LOG_DATA_DATA {
17524 pub const ENCODED_LEN: usize = 97usize;
17525 pub const DEFAULT: Self = Self {
17526 ofs: 0_u32,
17527 id: 0_u16,
17528 count: 0_u8,
17529 data: [0_u8; 90usize],
17530 };
17531 #[cfg(feature = "arbitrary")]
17532 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17533 use arbitrary::{Arbitrary, Unstructured};
17534 let mut buf = [0u8; 1024];
17535 rng.fill_bytes(&mut buf);
17536 let mut unstructured = Unstructured::new(&buf);
17537 Self::arbitrary(&mut unstructured).unwrap_or_default()
17538 }
17539}
17540impl Default for LOG_DATA_DATA {
17541 fn default() -> Self {
17542 Self::DEFAULT.clone()
17543 }
17544}
17545impl MessageData for LOG_DATA_DATA {
17546 type Message = MavMessage;
17547 const ID: u32 = 120u32;
17548 const NAME: &'static str = "LOG_DATA";
17549 const EXTRA_CRC: u8 = 134u8;
17550 const ENCODED_LEN: usize = 97usize;
17551 fn deser(
17552 _version: MavlinkVersion,
17553 __input: &[u8],
17554 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17555 let avail_len = __input.len();
17556 let mut payload_buf = [0; Self::ENCODED_LEN];
17557 let mut buf = if avail_len < Self::ENCODED_LEN {
17558 payload_buf[0..avail_len].copy_from_slice(__input);
17559 Bytes::new(&payload_buf)
17560 } else {
17561 Bytes::new(__input)
17562 };
17563 let mut __struct = Self::default();
17564 __struct.ofs = buf.get_u32_le();
17565 __struct.id = buf.get_u16_le();
17566 __struct.count = buf.get_u8();
17567 for v in &mut __struct.data {
17568 let val = buf.get_u8();
17569 *v = val;
17570 }
17571 Ok(__struct)
17572 }
17573 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17574 let mut __tmp = BytesMut::new(bytes);
17575 #[allow(clippy::absurd_extreme_comparisons)]
17576 #[allow(unused_comparisons)]
17577 if __tmp.remaining() < Self::ENCODED_LEN {
17578 panic!(
17579 "buffer is too small (need {} bytes, but got {})",
17580 Self::ENCODED_LEN,
17581 __tmp.remaining(),
17582 )
17583 }
17584 __tmp.put_u32_le(self.ofs);
17585 __tmp.put_u16_le(self.id);
17586 __tmp.put_u8(self.count);
17587 for val in &self.data {
17588 __tmp.put_u8(*val);
17589 }
17590 if matches!(version, MavlinkVersion::V2) {
17591 let len = __tmp.len();
17592 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17593 } else {
17594 __tmp.len()
17595 }
17596 }
17597}
17598#[doc = "id: 118"]
17599#[doc = "Reply to LOG_REQUEST_LIST."]
17600#[derive(Debug, Clone, PartialEq)]
17601#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17602#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17603pub struct LOG_ENTRY_DATA {
17604 #[doc = "UTC timestamp of log since 1970, or 0 if not available"]
17605 pub time_utc: u32,
17606 #[doc = "Size of the log (may be approximate)"]
17607 pub size: u32,
17608 #[doc = "Log id"]
17609 pub id: u16,
17610 #[doc = "Total number of logs"]
17611 pub num_logs: u16,
17612 #[doc = "High log number"]
17613 pub last_log_num: u16,
17614}
17615impl LOG_ENTRY_DATA {
17616 pub const ENCODED_LEN: usize = 14usize;
17617 pub const DEFAULT: Self = Self {
17618 time_utc: 0_u32,
17619 size: 0_u32,
17620 id: 0_u16,
17621 num_logs: 0_u16,
17622 last_log_num: 0_u16,
17623 };
17624 #[cfg(feature = "arbitrary")]
17625 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17626 use arbitrary::{Arbitrary, Unstructured};
17627 let mut buf = [0u8; 1024];
17628 rng.fill_bytes(&mut buf);
17629 let mut unstructured = Unstructured::new(&buf);
17630 Self::arbitrary(&mut unstructured).unwrap_or_default()
17631 }
17632}
17633impl Default for LOG_ENTRY_DATA {
17634 fn default() -> Self {
17635 Self::DEFAULT.clone()
17636 }
17637}
17638impl MessageData for LOG_ENTRY_DATA {
17639 type Message = MavMessage;
17640 const ID: u32 = 118u32;
17641 const NAME: &'static str = "LOG_ENTRY";
17642 const EXTRA_CRC: u8 = 56u8;
17643 const ENCODED_LEN: usize = 14usize;
17644 fn deser(
17645 _version: MavlinkVersion,
17646 __input: &[u8],
17647 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17648 let avail_len = __input.len();
17649 let mut payload_buf = [0; Self::ENCODED_LEN];
17650 let mut buf = if avail_len < Self::ENCODED_LEN {
17651 payload_buf[0..avail_len].copy_from_slice(__input);
17652 Bytes::new(&payload_buf)
17653 } else {
17654 Bytes::new(__input)
17655 };
17656 let mut __struct = Self::default();
17657 __struct.time_utc = buf.get_u32_le();
17658 __struct.size = buf.get_u32_le();
17659 __struct.id = buf.get_u16_le();
17660 __struct.num_logs = buf.get_u16_le();
17661 __struct.last_log_num = buf.get_u16_le();
17662 Ok(__struct)
17663 }
17664 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17665 let mut __tmp = BytesMut::new(bytes);
17666 #[allow(clippy::absurd_extreme_comparisons)]
17667 #[allow(unused_comparisons)]
17668 if __tmp.remaining() < Self::ENCODED_LEN {
17669 panic!(
17670 "buffer is too small (need {} bytes, but got {})",
17671 Self::ENCODED_LEN,
17672 __tmp.remaining(),
17673 )
17674 }
17675 __tmp.put_u32_le(self.time_utc);
17676 __tmp.put_u32_le(self.size);
17677 __tmp.put_u16_le(self.id);
17678 __tmp.put_u16_le(self.num_logs);
17679 __tmp.put_u16_le(self.last_log_num);
17680 if matches!(version, MavlinkVersion::V2) {
17681 let len = __tmp.len();
17682 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17683 } else {
17684 __tmp.len()
17685 }
17686 }
17687}
17688#[doc = "id: 121"]
17689#[doc = "Erase all logs."]
17690#[derive(Debug, Clone, PartialEq)]
17691#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17692#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17693pub struct LOG_ERASE_DATA {
17694 #[doc = "System ID"]
17695 pub target_system: u8,
17696 #[doc = "Component ID"]
17697 pub target_component: u8,
17698}
17699impl LOG_ERASE_DATA {
17700 pub const ENCODED_LEN: usize = 2usize;
17701 pub const DEFAULT: Self = Self {
17702 target_system: 0_u8,
17703 target_component: 0_u8,
17704 };
17705 #[cfg(feature = "arbitrary")]
17706 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17707 use arbitrary::{Arbitrary, Unstructured};
17708 let mut buf = [0u8; 1024];
17709 rng.fill_bytes(&mut buf);
17710 let mut unstructured = Unstructured::new(&buf);
17711 Self::arbitrary(&mut unstructured).unwrap_or_default()
17712 }
17713}
17714impl Default for LOG_ERASE_DATA {
17715 fn default() -> Self {
17716 Self::DEFAULT.clone()
17717 }
17718}
17719impl MessageData for LOG_ERASE_DATA {
17720 type Message = MavMessage;
17721 const ID: u32 = 121u32;
17722 const NAME: &'static str = "LOG_ERASE";
17723 const EXTRA_CRC: u8 = 237u8;
17724 const ENCODED_LEN: usize = 2usize;
17725 fn deser(
17726 _version: MavlinkVersion,
17727 __input: &[u8],
17728 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17729 let avail_len = __input.len();
17730 let mut payload_buf = [0; Self::ENCODED_LEN];
17731 let mut buf = if avail_len < Self::ENCODED_LEN {
17732 payload_buf[0..avail_len].copy_from_slice(__input);
17733 Bytes::new(&payload_buf)
17734 } else {
17735 Bytes::new(__input)
17736 };
17737 let mut __struct = Self::default();
17738 __struct.target_system = buf.get_u8();
17739 __struct.target_component = buf.get_u8();
17740 Ok(__struct)
17741 }
17742 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17743 let mut __tmp = BytesMut::new(bytes);
17744 #[allow(clippy::absurd_extreme_comparisons)]
17745 #[allow(unused_comparisons)]
17746 if __tmp.remaining() < Self::ENCODED_LEN {
17747 panic!(
17748 "buffer is too small (need {} bytes, but got {})",
17749 Self::ENCODED_LEN,
17750 __tmp.remaining(),
17751 )
17752 }
17753 __tmp.put_u8(self.target_system);
17754 __tmp.put_u8(self.target_component);
17755 if matches!(version, MavlinkVersion::V2) {
17756 let len = __tmp.len();
17757 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17758 } else {
17759 __tmp.len()
17760 }
17761 }
17762}
17763#[doc = "id: 119"]
17764#[doc = "Request a chunk of a log."]
17765#[derive(Debug, Clone, PartialEq)]
17766#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17767#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17768pub struct LOG_REQUEST_DATA_DATA {
17769 #[doc = "Offset into the log"]
17770 pub ofs: u32,
17771 #[doc = "Number of bytes"]
17772 pub count: u32,
17773 #[doc = "Log id (from LOG_ENTRY reply)"]
17774 pub id: u16,
17775 #[doc = "System ID"]
17776 pub target_system: u8,
17777 #[doc = "Component ID"]
17778 pub target_component: u8,
17779}
17780impl LOG_REQUEST_DATA_DATA {
17781 pub const ENCODED_LEN: usize = 12usize;
17782 pub const DEFAULT: Self = Self {
17783 ofs: 0_u32,
17784 count: 0_u32,
17785 id: 0_u16,
17786 target_system: 0_u8,
17787 target_component: 0_u8,
17788 };
17789 #[cfg(feature = "arbitrary")]
17790 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17791 use arbitrary::{Arbitrary, Unstructured};
17792 let mut buf = [0u8; 1024];
17793 rng.fill_bytes(&mut buf);
17794 let mut unstructured = Unstructured::new(&buf);
17795 Self::arbitrary(&mut unstructured).unwrap_or_default()
17796 }
17797}
17798impl Default for LOG_REQUEST_DATA_DATA {
17799 fn default() -> Self {
17800 Self::DEFAULT.clone()
17801 }
17802}
17803impl MessageData for LOG_REQUEST_DATA_DATA {
17804 type Message = MavMessage;
17805 const ID: u32 = 119u32;
17806 const NAME: &'static str = "LOG_REQUEST_DATA";
17807 const EXTRA_CRC: u8 = 116u8;
17808 const ENCODED_LEN: usize = 12usize;
17809 fn deser(
17810 _version: MavlinkVersion,
17811 __input: &[u8],
17812 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17813 let avail_len = __input.len();
17814 let mut payload_buf = [0; Self::ENCODED_LEN];
17815 let mut buf = if avail_len < Self::ENCODED_LEN {
17816 payload_buf[0..avail_len].copy_from_slice(__input);
17817 Bytes::new(&payload_buf)
17818 } else {
17819 Bytes::new(__input)
17820 };
17821 let mut __struct = Self::default();
17822 __struct.ofs = buf.get_u32_le();
17823 __struct.count = buf.get_u32_le();
17824 __struct.id = buf.get_u16_le();
17825 __struct.target_system = buf.get_u8();
17826 __struct.target_component = buf.get_u8();
17827 Ok(__struct)
17828 }
17829 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17830 let mut __tmp = BytesMut::new(bytes);
17831 #[allow(clippy::absurd_extreme_comparisons)]
17832 #[allow(unused_comparisons)]
17833 if __tmp.remaining() < Self::ENCODED_LEN {
17834 panic!(
17835 "buffer is too small (need {} bytes, but got {})",
17836 Self::ENCODED_LEN,
17837 __tmp.remaining(),
17838 )
17839 }
17840 __tmp.put_u32_le(self.ofs);
17841 __tmp.put_u32_le(self.count);
17842 __tmp.put_u16_le(self.id);
17843 __tmp.put_u8(self.target_system);
17844 __tmp.put_u8(self.target_component);
17845 if matches!(version, MavlinkVersion::V2) {
17846 let len = __tmp.len();
17847 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17848 } else {
17849 __tmp.len()
17850 }
17851 }
17852}
17853#[doc = "id: 122"]
17854#[doc = "Stop log transfer and resume normal logging."]
17855#[derive(Debug, Clone, PartialEq)]
17856#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17857#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17858pub struct LOG_REQUEST_END_DATA {
17859 #[doc = "System ID"]
17860 pub target_system: u8,
17861 #[doc = "Component ID"]
17862 pub target_component: u8,
17863}
17864impl LOG_REQUEST_END_DATA {
17865 pub const ENCODED_LEN: usize = 2usize;
17866 pub const DEFAULT: Self = Self {
17867 target_system: 0_u8,
17868 target_component: 0_u8,
17869 };
17870 #[cfg(feature = "arbitrary")]
17871 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17872 use arbitrary::{Arbitrary, Unstructured};
17873 let mut buf = [0u8; 1024];
17874 rng.fill_bytes(&mut buf);
17875 let mut unstructured = Unstructured::new(&buf);
17876 Self::arbitrary(&mut unstructured).unwrap_or_default()
17877 }
17878}
17879impl Default for LOG_REQUEST_END_DATA {
17880 fn default() -> Self {
17881 Self::DEFAULT.clone()
17882 }
17883}
17884impl MessageData for LOG_REQUEST_END_DATA {
17885 type Message = MavMessage;
17886 const ID: u32 = 122u32;
17887 const NAME: &'static str = "LOG_REQUEST_END";
17888 const EXTRA_CRC: u8 = 203u8;
17889 const ENCODED_LEN: usize = 2usize;
17890 fn deser(
17891 _version: MavlinkVersion,
17892 __input: &[u8],
17893 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17894 let avail_len = __input.len();
17895 let mut payload_buf = [0; Self::ENCODED_LEN];
17896 let mut buf = if avail_len < Self::ENCODED_LEN {
17897 payload_buf[0..avail_len].copy_from_slice(__input);
17898 Bytes::new(&payload_buf)
17899 } else {
17900 Bytes::new(__input)
17901 };
17902 let mut __struct = Self::default();
17903 __struct.target_system = buf.get_u8();
17904 __struct.target_component = buf.get_u8();
17905 Ok(__struct)
17906 }
17907 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17908 let mut __tmp = BytesMut::new(bytes);
17909 #[allow(clippy::absurd_extreme_comparisons)]
17910 #[allow(unused_comparisons)]
17911 if __tmp.remaining() < Self::ENCODED_LEN {
17912 panic!(
17913 "buffer is too small (need {} bytes, but got {})",
17914 Self::ENCODED_LEN,
17915 __tmp.remaining(),
17916 )
17917 }
17918 __tmp.put_u8(self.target_system);
17919 __tmp.put_u8(self.target_component);
17920 if matches!(version, MavlinkVersion::V2) {
17921 let len = __tmp.len();
17922 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17923 } else {
17924 __tmp.len()
17925 }
17926 }
17927}
17928#[doc = "id: 117"]
17929#[doc = "Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called. If there are no log files available this request shall be answered with one LOG_ENTRY message with id = 0 and num_logs = 0."]
17930#[derive(Debug, Clone, PartialEq)]
17931#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17932#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17933pub struct LOG_REQUEST_LIST_DATA {
17934 #[doc = "First log id (0 for first available)"]
17935 pub start: u16,
17936 #[doc = "Last log id (0xffff for last available)"]
17937 pub end: u16,
17938 #[doc = "System ID"]
17939 pub target_system: u8,
17940 #[doc = "Component ID"]
17941 pub target_component: u8,
17942}
17943impl LOG_REQUEST_LIST_DATA {
17944 pub const ENCODED_LEN: usize = 6usize;
17945 pub const DEFAULT: Self = Self {
17946 start: 0_u16,
17947 end: 0_u16,
17948 target_system: 0_u8,
17949 target_component: 0_u8,
17950 };
17951 #[cfg(feature = "arbitrary")]
17952 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17953 use arbitrary::{Arbitrary, Unstructured};
17954 let mut buf = [0u8; 1024];
17955 rng.fill_bytes(&mut buf);
17956 let mut unstructured = Unstructured::new(&buf);
17957 Self::arbitrary(&mut unstructured).unwrap_or_default()
17958 }
17959}
17960impl Default for LOG_REQUEST_LIST_DATA {
17961 fn default() -> Self {
17962 Self::DEFAULT.clone()
17963 }
17964}
17965impl MessageData for LOG_REQUEST_LIST_DATA {
17966 type Message = MavMessage;
17967 const ID: u32 = 117u32;
17968 const NAME: &'static str = "LOG_REQUEST_LIST";
17969 const EXTRA_CRC: u8 = 128u8;
17970 const ENCODED_LEN: usize = 6usize;
17971 fn deser(
17972 _version: MavlinkVersion,
17973 __input: &[u8],
17974 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17975 let avail_len = __input.len();
17976 let mut payload_buf = [0; Self::ENCODED_LEN];
17977 let mut buf = if avail_len < Self::ENCODED_LEN {
17978 payload_buf[0..avail_len].copy_from_slice(__input);
17979 Bytes::new(&payload_buf)
17980 } else {
17981 Bytes::new(__input)
17982 };
17983 let mut __struct = Self::default();
17984 __struct.start = buf.get_u16_le();
17985 __struct.end = buf.get_u16_le();
17986 __struct.target_system = buf.get_u8();
17987 __struct.target_component = buf.get_u8();
17988 Ok(__struct)
17989 }
17990 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17991 let mut __tmp = BytesMut::new(bytes);
17992 #[allow(clippy::absurd_extreme_comparisons)]
17993 #[allow(unused_comparisons)]
17994 if __tmp.remaining() < Self::ENCODED_LEN {
17995 panic!(
17996 "buffer is too small (need {} bytes, but got {})",
17997 Self::ENCODED_LEN,
17998 __tmp.remaining(),
17999 )
18000 }
18001 __tmp.put_u16_le(self.start);
18002 __tmp.put_u16_le(self.end);
18003 __tmp.put_u8(self.target_system);
18004 __tmp.put_u8(self.target_component);
18005 if matches!(version, MavlinkVersion::V2) {
18006 let len = __tmp.len();
18007 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18008 } else {
18009 __tmp.len()
18010 }
18011 }
18012}
18013#[doc = "id: 192"]
18014#[doc = "Reports results of completed compass calibration. Sent until MAG_CAL_ACK received."]
18015#[derive(Debug, Clone, PartialEq)]
18016#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18017#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18018pub struct MAG_CAL_REPORT_DATA {
18019 #[doc = "RMS milligauss residuals."]
18020 pub fitness: f32,
18021 #[doc = "X offset."]
18022 pub ofs_x: f32,
18023 #[doc = "Y offset."]
18024 pub ofs_y: f32,
18025 #[doc = "Z offset."]
18026 pub ofs_z: f32,
18027 #[doc = "X diagonal (matrix 11)."]
18028 pub diag_x: f32,
18029 #[doc = "Y diagonal (matrix 22)."]
18030 pub diag_y: f32,
18031 #[doc = "Z diagonal (matrix 33)."]
18032 pub diag_z: f32,
18033 #[doc = "X off-diagonal (matrix 12 and 21)."]
18034 pub offdiag_x: f32,
18035 #[doc = "Y off-diagonal (matrix 13 and 31)."]
18036 pub offdiag_y: f32,
18037 #[doc = "Z off-diagonal (matrix 32 and 23)."]
18038 pub offdiag_z: f32,
18039 #[doc = "Compass being calibrated."]
18040 pub compass_id: u8,
18041 #[doc = "Bitmask of compasses being calibrated."]
18042 pub cal_mask: u8,
18043 #[doc = "Calibration Status."]
18044 pub cal_status: MagCalStatus,
18045 #[doc = "0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters."]
18046 pub autosaved: u8,
18047 #[doc = "Confidence in orientation (higher is better)."]
18048 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18049 pub orientation_confidence: f32,
18050 #[doc = "orientation before calibration."]
18051 #[cfg_attr(feature = "serde", serde(default))]
18052 pub old_orientation: MavSensorOrientation,
18053 #[doc = "orientation after calibration."]
18054 #[cfg_attr(feature = "serde", serde(default))]
18055 pub new_orientation: MavSensorOrientation,
18056 #[doc = "field radius correction factor"]
18057 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18058 pub scale_factor: f32,
18059}
18060impl MAG_CAL_REPORT_DATA {
18061 pub const ENCODED_LEN: usize = 54usize;
18062 pub const DEFAULT: Self = Self {
18063 fitness: 0.0_f32,
18064 ofs_x: 0.0_f32,
18065 ofs_y: 0.0_f32,
18066 ofs_z: 0.0_f32,
18067 diag_x: 0.0_f32,
18068 diag_y: 0.0_f32,
18069 diag_z: 0.0_f32,
18070 offdiag_x: 0.0_f32,
18071 offdiag_y: 0.0_f32,
18072 offdiag_z: 0.0_f32,
18073 compass_id: 0_u8,
18074 cal_mask: 0_u8,
18075 cal_status: MagCalStatus::DEFAULT,
18076 autosaved: 0_u8,
18077 orientation_confidence: 0.0_f32,
18078 old_orientation: MavSensorOrientation::DEFAULT,
18079 new_orientation: MavSensorOrientation::DEFAULT,
18080 scale_factor: 0.0_f32,
18081 };
18082 #[cfg(feature = "arbitrary")]
18083 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18084 use arbitrary::{Arbitrary, Unstructured};
18085 let mut buf = [0u8; 1024];
18086 rng.fill_bytes(&mut buf);
18087 let mut unstructured = Unstructured::new(&buf);
18088 Self::arbitrary(&mut unstructured).unwrap_or_default()
18089 }
18090}
18091impl Default for MAG_CAL_REPORT_DATA {
18092 fn default() -> Self {
18093 Self::DEFAULT.clone()
18094 }
18095}
18096impl MessageData for MAG_CAL_REPORT_DATA {
18097 type Message = MavMessage;
18098 const ID: u32 = 192u32;
18099 const NAME: &'static str = "MAG_CAL_REPORT";
18100 const EXTRA_CRC: u8 = 36u8;
18101 const ENCODED_LEN: usize = 54usize;
18102 fn deser(
18103 _version: MavlinkVersion,
18104 __input: &[u8],
18105 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18106 let avail_len = __input.len();
18107 let mut payload_buf = [0; Self::ENCODED_LEN];
18108 let mut buf = if avail_len < Self::ENCODED_LEN {
18109 payload_buf[0..avail_len].copy_from_slice(__input);
18110 Bytes::new(&payload_buf)
18111 } else {
18112 Bytes::new(__input)
18113 };
18114 let mut __struct = Self::default();
18115 __struct.fitness = buf.get_f32_le();
18116 __struct.ofs_x = buf.get_f32_le();
18117 __struct.ofs_y = buf.get_f32_le();
18118 __struct.ofs_z = buf.get_f32_le();
18119 __struct.diag_x = buf.get_f32_le();
18120 __struct.diag_y = buf.get_f32_le();
18121 __struct.diag_z = buf.get_f32_le();
18122 __struct.offdiag_x = buf.get_f32_le();
18123 __struct.offdiag_y = buf.get_f32_le();
18124 __struct.offdiag_z = buf.get_f32_le();
18125 __struct.compass_id = buf.get_u8();
18126 __struct.cal_mask = buf.get_u8();
18127 let tmp = buf.get_u8();
18128 __struct.cal_status =
18129 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18130 enum_type: "MagCalStatus",
18131 value: tmp as u32,
18132 })?;
18133 __struct.autosaved = buf.get_u8();
18134 __struct.orientation_confidence = buf.get_f32_le();
18135 let tmp = buf.get_u8();
18136 __struct.old_orientation =
18137 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18138 enum_type: "MavSensorOrientation",
18139 value: tmp as u32,
18140 })?;
18141 let tmp = buf.get_u8();
18142 __struct.new_orientation =
18143 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18144 enum_type: "MavSensorOrientation",
18145 value: tmp as u32,
18146 })?;
18147 __struct.scale_factor = buf.get_f32_le();
18148 Ok(__struct)
18149 }
18150 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18151 let mut __tmp = BytesMut::new(bytes);
18152 #[allow(clippy::absurd_extreme_comparisons)]
18153 #[allow(unused_comparisons)]
18154 if __tmp.remaining() < Self::ENCODED_LEN {
18155 panic!(
18156 "buffer is too small (need {} bytes, but got {})",
18157 Self::ENCODED_LEN,
18158 __tmp.remaining(),
18159 )
18160 }
18161 __tmp.put_f32_le(self.fitness);
18162 __tmp.put_f32_le(self.ofs_x);
18163 __tmp.put_f32_le(self.ofs_y);
18164 __tmp.put_f32_le(self.ofs_z);
18165 __tmp.put_f32_le(self.diag_x);
18166 __tmp.put_f32_le(self.diag_y);
18167 __tmp.put_f32_le(self.diag_z);
18168 __tmp.put_f32_le(self.offdiag_x);
18169 __tmp.put_f32_le(self.offdiag_y);
18170 __tmp.put_f32_le(self.offdiag_z);
18171 __tmp.put_u8(self.compass_id);
18172 __tmp.put_u8(self.cal_mask);
18173 __tmp.put_u8(self.cal_status as u8);
18174 __tmp.put_u8(self.autosaved);
18175 __tmp.put_f32_le(self.orientation_confidence);
18176 __tmp.put_u8(self.old_orientation as u8);
18177 __tmp.put_u8(self.new_orientation as u8);
18178 __tmp.put_f32_le(self.scale_factor);
18179 if matches!(version, MavlinkVersion::V2) {
18180 let len = __tmp.len();
18181 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18182 } else {
18183 __tmp.len()
18184 }
18185 }
18186}
18187#[doc = "id: 69"]
18188#[doc = "This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled and buttons states are transmitted as individual on/off bits of a bitmask."]
18189#[derive(Debug, Clone, PartialEq)]
18190#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18191#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18192pub struct MANUAL_CONTROL_DATA {
18193 #[doc = "X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle."]
18194 pub x: i16,
18195 #[doc = "Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle."]
18196 pub y: i16,
18197 #[doc = "Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust."]
18198 pub z: i16,
18199 #[doc = "R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle."]
18200 pub r: i16,
18201 #[doc = "A bitfield corresponding to the joystick buttons' 0-15 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1."]
18202 pub buttons: u16,
18203 #[doc = "The system to be controlled."]
18204 pub target: u8,
18205 #[doc = "A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16."]
18206 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18207 pub buttons2: u16,
18208 #[doc = "Set bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll, bit 2: aux1, bit 3: aux2, bit 4: aux3, bit 5: aux4, bit 6: aux5, bit 7: aux6"]
18209 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18210 pub enabled_extensions: u8,
18211 #[doc = "Pitch-only-axis, normalized to the range [-1000,1000]. Generally corresponds to pitch on vehicles with additional degrees of freedom. Valid if bit 0 of enabled_extensions field is set. Set to 0 if invalid."]
18212 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18213 pub s: i16,
18214 #[doc = "Roll-only-axis, normalized to the range [-1000,1000]. Generally corresponds to roll on vehicles with additional degrees of freedom. Valid if bit 1 of enabled_extensions field is set. Set to 0 if invalid."]
18215 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18216 pub t: i16,
18217 #[doc = "Aux continuous input field 1. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 2 of enabled_extensions field is set. 0 if bit 2 is unset."]
18218 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18219 pub aux1: i16,
18220 #[doc = "Aux continuous input field 2. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 3 of enabled_extensions field is set. 0 if bit 3 is unset."]
18221 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18222 pub aux2: i16,
18223 #[doc = "Aux continuous input field 3. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 4 of enabled_extensions field is set. 0 if bit 4 is unset."]
18224 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18225 pub aux3: i16,
18226 #[doc = "Aux continuous input field 4. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 5 of enabled_extensions field is set. 0 if bit 5 is unset."]
18227 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18228 pub aux4: i16,
18229 #[doc = "Aux continuous input field 5. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 6 of enabled_extensions field is set. 0 if bit 6 is unset."]
18230 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18231 pub aux5: i16,
18232 #[doc = "Aux continuous input field 6. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 7 of enabled_extensions field is set. 0 if bit 7 is unset."]
18233 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18234 pub aux6: i16,
18235}
18236impl MANUAL_CONTROL_DATA {
18237 pub const ENCODED_LEN: usize = 30usize;
18238 pub const DEFAULT: Self = Self {
18239 x: 0_i16,
18240 y: 0_i16,
18241 z: 0_i16,
18242 r: 0_i16,
18243 buttons: 0_u16,
18244 target: 0_u8,
18245 buttons2: 0_u16,
18246 enabled_extensions: 0_u8,
18247 s: 0_i16,
18248 t: 0_i16,
18249 aux1: 0_i16,
18250 aux2: 0_i16,
18251 aux3: 0_i16,
18252 aux4: 0_i16,
18253 aux5: 0_i16,
18254 aux6: 0_i16,
18255 };
18256 #[cfg(feature = "arbitrary")]
18257 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18258 use arbitrary::{Arbitrary, Unstructured};
18259 let mut buf = [0u8; 1024];
18260 rng.fill_bytes(&mut buf);
18261 let mut unstructured = Unstructured::new(&buf);
18262 Self::arbitrary(&mut unstructured).unwrap_or_default()
18263 }
18264}
18265impl Default for MANUAL_CONTROL_DATA {
18266 fn default() -> Self {
18267 Self::DEFAULT.clone()
18268 }
18269}
18270impl MessageData for MANUAL_CONTROL_DATA {
18271 type Message = MavMessage;
18272 const ID: u32 = 69u32;
18273 const NAME: &'static str = "MANUAL_CONTROL";
18274 const EXTRA_CRC: u8 = 243u8;
18275 const ENCODED_LEN: usize = 30usize;
18276 fn deser(
18277 _version: MavlinkVersion,
18278 __input: &[u8],
18279 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18280 let avail_len = __input.len();
18281 let mut payload_buf = [0; Self::ENCODED_LEN];
18282 let mut buf = if avail_len < Self::ENCODED_LEN {
18283 payload_buf[0..avail_len].copy_from_slice(__input);
18284 Bytes::new(&payload_buf)
18285 } else {
18286 Bytes::new(__input)
18287 };
18288 let mut __struct = Self::default();
18289 __struct.x = buf.get_i16_le();
18290 __struct.y = buf.get_i16_le();
18291 __struct.z = buf.get_i16_le();
18292 __struct.r = buf.get_i16_le();
18293 __struct.buttons = buf.get_u16_le();
18294 __struct.target = buf.get_u8();
18295 __struct.buttons2 = buf.get_u16_le();
18296 __struct.enabled_extensions = buf.get_u8();
18297 __struct.s = buf.get_i16_le();
18298 __struct.t = buf.get_i16_le();
18299 __struct.aux1 = buf.get_i16_le();
18300 __struct.aux2 = buf.get_i16_le();
18301 __struct.aux3 = buf.get_i16_le();
18302 __struct.aux4 = buf.get_i16_le();
18303 __struct.aux5 = buf.get_i16_le();
18304 __struct.aux6 = buf.get_i16_le();
18305 Ok(__struct)
18306 }
18307 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18308 let mut __tmp = BytesMut::new(bytes);
18309 #[allow(clippy::absurd_extreme_comparisons)]
18310 #[allow(unused_comparisons)]
18311 if __tmp.remaining() < Self::ENCODED_LEN {
18312 panic!(
18313 "buffer is too small (need {} bytes, but got {})",
18314 Self::ENCODED_LEN,
18315 __tmp.remaining(),
18316 )
18317 }
18318 __tmp.put_i16_le(self.x);
18319 __tmp.put_i16_le(self.y);
18320 __tmp.put_i16_le(self.z);
18321 __tmp.put_i16_le(self.r);
18322 __tmp.put_u16_le(self.buttons);
18323 __tmp.put_u8(self.target);
18324 __tmp.put_u16_le(self.buttons2);
18325 __tmp.put_u8(self.enabled_extensions);
18326 __tmp.put_i16_le(self.s);
18327 __tmp.put_i16_le(self.t);
18328 __tmp.put_i16_le(self.aux1);
18329 __tmp.put_i16_le(self.aux2);
18330 __tmp.put_i16_le(self.aux3);
18331 __tmp.put_i16_le(self.aux4);
18332 __tmp.put_i16_le(self.aux5);
18333 __tmp.put_i16_le(self.aux6);
18334 if matches!(version, MavlinkVersion::V2) {
18335 let len = __tmp.len();
18336 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18337 } else {
18338 __tmp.len()
18339 }
18340 }
18341}
18342#[doc = "id: 81"]
18343#[doc = "Setpoint in roll, pitch, yaw and thrust from the operator."]
18344#[derive(Debug, Clone, PartialEq)]
18345#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18346#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18347pub struct MANUAL_SETPOINT_DATA {
18348 #[doc = "Timestamp (time since system boot)."]
18349 pub time_boot_ms: u32,
18350 #[doc = "Desired roll rate"]
18351 pub roll: f32,
18352 #[doc = "Desired pitch rate"]
18353 pub pitch: f32,
18354 #[doc = "Desired yaw rate"]
18355 pub yaw: f32,
18356 #[doc = "Collective thrust, normalized to 0 .. 1"]
18357 pub thrust: f32,
18358 #[doc = "Flight mode switch position, 0.. 255"]
18359 pub mode_switch: u8,
18360 #[doc = "Override mode switch position, 0.. 255"]
18361 pub manual_override_switch: u8,
18362}
18363impl MANUAL_SETPOINT_DATA {
18364 pub const ENCODED_LEN: usize = 22usize;
18365 pub const DEFAULT: Self = Self {
18366 time_boot_ms: 0_u32,
18367 roll: 0.0_f32,
18368 pitch: 0.0_f32,
18369 yaw: 0.0_f32,
18370 thrust: 0.0_f32,
18371 mode_switch: 0_u8,
18372 manual_override_switch: 0_u8,
18373 };
18374 #[cfg(feature = "arbitrary")]
18375 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18376 use arbitrary::{Arbitrary, Unstructured};
18377 let mut buf = [0u8; 1024];
18378 rng.fill_bytes(&mut buf);
18379 let mut unstructured = Unstructured::new(&buf);
18380 Self::arbitrary(&mut unstructured).unwrap_or_default()
18381 }
18382}
18383impl Default for MANUAL_SETPOINT_DATA {
18384 fn default() -> Self {
18385 Self::DEFAULT.clone()
18386 }
18387}
18388impl MessageData for MANUAL_SETPOINT_DATA {
18389 type Message = MavMessage;
18390 const ID: u32 = 81u32;
18391 const NAME: &'static str = "MANUAL_SETPOINT";
18392 const EXTRA_CRC: u8 = 106u8;
18393 const ENCODED_LEN: usize = 22usize;
18394 fn deser(
18395 _version: MavlinkVersion,
18396 __input: &[u8],
18397 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18398 let avail_len = __input.len();
18399 let mut payload_buf = [0; Self::ENCODED_LEN];
18400 let mut buf = if avail_len < Self::ENCODED_LEN {
18401 payload_buf[0..avail_len].copy_from_slice(__input);
18402 Bytes::new(&payload_buf)
18403 } else {
18404 Bytes::new(__input)
18405 };
18406 let mut __struct = Self::default();
18407 __struct.time_boot_ms = buf.get_u32_le();
18408 __struct.roll = buf.get_f32_le();
18409 __struct.pitch = buf.get_f32_le();
18410 __struct.yaw = buf.get_f32_le();
18411 __struct.thrust = buf.get_f32_le();
18412 __struct.mode_switch = buf.get_u8();
18413 __struct.manual_override_switch = buf.get_u8();
18414 Ok(__struct)
18415 }
18416 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18417 let mut __tmp = BytesMut::new(bytes);
18418 #[allow(clippy::absurd_extreme_comparisons)]
18419 #[allow(unused_comparisons)]
18420 if __tmp.remaining() < Self::ENCODED_LEN {
18421 panic!(
18422 "buffer is too small (need {} bytes, but got {})",
18423 Self::ENCODED_LEN,
18424 __tmp.remaining(),
18425 )
18426 }
18427 __tmp.put_u32_le(self.time_boot_ms);
18428 __tmp.put_f32_le(self.roll);
18429 __tmp.put_f32_le(self.pitch);
18430 __tmp.put_f32_le(self.yaw);
18431 __tmp.put_f32_le(self.thrust);
18432 __tmp.put_u8(self.mode_switch);
18433 __tmp.put_u8(self.manual_override_switch);
18434 if matches!(version, MavlinkVersion::V2) {
18435 let len = __tmp.len();
18436 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18437 } else {
18438 __tmp.len()
18439 }
18440 }
18441}
18442#[doc = "id: 249"]
18443#[doc = "Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output."]
18444#[derive(Debug, Clone, PartialEq)]
18445#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18446#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18447pub struct MEMORY_VECT_DATA {
18448 #[doc = "Starting address of the debug variables"]
18449 pub address: u16,
18450 #[doc = "Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below"]
18451 pub ver: u8,
18452 #[doc = "Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14"]
18453 pub mavtype: u8,
18454 #[doc = "Memory contents at specified address"]
18455 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18456 pub value: [i8; 32],
18457}
18458impl MEMORY_VECT_DATA {
18459 pub const ENCODED_LEN: usize = 36usize;
18460 pub const DEFAULT: Self = Self {
18461 address: 0_u16,
18462 ver: 0_u8,
18463 mavtype: 0_u8,
18464 value: [0_i8; 32usize],
18465 };
18466 #[cfg(feature = "arbitrary")]
18467 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18468 use arbitrary::{Arbitrary, Unstructured};
18469 let mut buf = [0u8; 1024];
18470 rng.fill_bytes(&mut buf);
18471 let mut unstructured = Unstructured::new(&buf);
18472 Self::arbitrary(&mut unstructured).unwrap_or_default()
18473 }
18474}
18475impl Default for MEMORY_VECT_DATA {
18476 fn default() -> Self {
18477 Self::DEFAULT.clone()
18478 }
18479}
18480impl MessageData for MEMORY_VECT_DATA {
18481 type Message = MavMessage;
18482 const ID: u32 = 249u32;
18483 const NAME: &'static str = "MEMORY_VECT";
18484 const EXTRA_CRC: u8 = 204u8;
18485 const ENCODED_LEN: usize = 36usize;
18486 fn deser(
18487 _version: MavlinkVersion,
18488 __input: &[u8],
18489 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18490 let avail_len = __input.len();
18491 let mut payload_buf = [0; Self::ENCODED_LEN];
18492 let mut buf = if avail_len < Self::ENCODED_LEN {
18493 payload_buf[0..avail_len].copy_from_slice(__input);
18494 Bytes::new(&payload_buf)
18495 } else {
18496 Bytes::new(__input)
18497 };
18498 let mut __struct = Self::default();
18499 __struct.address = buf.get_u16_le();
18500 __struct.ver = buf.get_u8();
18501 __struct.mavtype = buf.get_u8();
18502 for v in &mut __struct.value {
18503 let val = buf.get_i8();
18504 *v = val;
18505 }
18506 Ok(__struct)
18507 }
18508 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18509 let mut __tmp = BytesMut::new(bytes);
18510 #[allow(clippy::absurd_extreme_comparisons)]
18511 #[allow(unused_comparisons)]
18512 if __tmp.remaining() < Self::ENCODED_LEN {
18513 panic!(
18514 "buffer is too small (need {} bytes, but got {})",
18515 Self::ENCODED_LEN,
18516 __tmp.remaining(),
18517 )
18518 }
18519 __tmp.put_u16_le(self.address);
18520 __tmp.put_u8(self.ver);
18521 __tmp.put_u8(self.mavtype);
18522 for val in &self.value {
18523 __tmp.put_i8(*val);
18524 }
18525 if matches!(version, MavlinkVersion::V2) {
18526 let len = __tmp.len();
18527 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18528 } else {
18529 __tmp.len()
18530 }
18531 }
18532}
18533#[doc = "id: 244"]
18534#[doc = "The interval between messages for a particular MAVLink message ID. This message is sent in response to the MAV_CMD_REQUEST_MESSAGE command with param1=244 (this message) and param2=message_id (the id of the message for which the interval is required). \tIt may also be sent in response to MAV_CMD_GET_MESSAGE_INTERVAL. \tThis interface replaces DATA_STREAM."]
18535#[derive(Debug, Clone, PartialEq)]
18536#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18537#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18538pub struct MESSAGE_INTERVAL_DATA {
18539 #[doc = "0 indicates the interval at which it is sent."]
18540 pub interval_us: i32,
18541 #[doc = "The ID of the requested MAVLink message. v1.0 is limited to 254 messages."]
18542 pub message_id: u16,
18543}
18544impl MESSAGE_INTERVAL_DATA {
18545 pub const ENCODED_LEN: usize = 6usize;
18546 pub const DEFAULT: Self = Self {
18547 interval_us: 0_i32,
18548 message_id: 0_u16,
18549 };
18550 #[cfg(feature = "arbitrary")]
18551 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18552 use arbitrary::{Arbitrary, Unstructured};
18553 let mut buf = [0u8; 1024];
18554 rng.fill_bytes(&mut buf);
18555 let mut unstructured = Unstructured::new(&buf);
18556 Self::arbitrary(&mut unstructured).unwrap_or_default()
18557 }
18558}
18559impl Default for MESSAGE_INTERVAL_DATA {
18560 fn default() -> Self {
18561 Self::DEFAULT.clone()
18562 }
18563}
18564impl MessageData for MESSAGE_INTERVAL_DATA {
18565 type Message = MavMessage;
18566 const ID: u32 = 244u32;
18567 const NAME: &'static str = "MESSAGE_INTERVAL";
18568 const EXTRA_CRC: u8 = 95u8;
18569 const ENCODED_LEN: usize = 6usize;
18570 fn deser(
18571 _version: MavlinkVersion,
18572 __input: &[u8],
18573 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18574 let avail_len = __input.len();
18575 let mut payload_buf = [0; Self::ENCODED_LEN];
18576 let mut buf = if avail_len < Self::ENCODED_LEN {
18577 payload_buf[0..avail_len].copy_from_slice(__input);
18578 Bytes::new(&payload_buf)
18579 } else {
18580 Bytes::new(__input)
18581 };
18582 let mut __struct = Self::default();
18583 __struct.interval_us = buf.get_i32_le();
18584 __struct.message_id = buf.get_u16_le();
18585 Ok(__struct)
18586 }
18587 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18588 let mut __tmp = BytesMut::new(bytes);
18589 #[allow(clippy::absurd_extreme_comparisons)]
18590 #[allow(unused_comparisons)]
18591 if __tmp.remaining() < Self::ENCODED_LEN {
18592 panic!(
18593 "buffer is too small (need {} bytes, but got {})",
18594 Self::ENCODED_LEN,
18595 __tmp.remaining(),
18596 )
18597 }
18598 __tmp.put_i32_le(self.interval_us);
18599 __tmp.put_u16_le(self.message_id);
18600 if matches!(version, MavlinkVersion::V2) {
18601 let len = __tmp.len();
18602 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18603 } else {
18604 __tmp.len()
18605 }
18606 }
18607}
18608#[doc = "id: 47"]
18609#[doc = "Acknowledgment message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero)."]
18610#[derive(Debug, Clone, PartialEq)]
18611#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18612#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18613pub struct MISSION_ACK_DATA {
18614 #[doc = "System ID"]
18615 pub target_system: u8,
18616 #[doc = "Component ID"]
18617 pub target_component: u8,
18618 #[doc = "Mission result."]
18619 pub mavtype: MavMissionResult,
18620 #[doc = "Mission type."]
18621 #[cfg_attr(feature = "serde", serde(default))]
18622 pub mission_type: MavMissionType,
18623 #[doc = "Id of new on-vehicle mission, fence, or rally point plan (on upload to vehicle). The id is calculated and returned by a vehicle when a new plan is uploaded by a GCS. The only requirement on the id is that it must change when there is any change to the on-vehicle plan type (there is no requirement that the id be globally unique). 0 on download from the vehicle to the GCS (on download the ID is set in MISSION_COUNT). 0 if plan ids are not supported. The current on-vehicle plan ids are streamed in `MISSION_CURRENT`, allowing a GCS to determine if any part of the plan has changed and needs to be re-uploaded."]
18624 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18625 pub opaque_id: u32,
18626}
18627impl MISSION_ACK_DATA {
18628 pub const ENCODED_LEN: usize = 8usize;
18629 pub const DEFAULT: Self = Self {
18630 target_system: 0_u8,
18631 target_component: 0_u8,
18632 mavtype: MavMissionResult::DEFAULT,
18633 mission_type: MavMissionType::DEFAULT,
18634 opaque_id: 0_u32,
18635 };
18636 #[cfg(feature = "arbitrary")]
18637 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18638 use arbitrary::{Arbitrary, Unstructured};
18639 let mut buf = [0u8; 1024];
18640 rng.fill_bytes(&mut buf);
18641 let mut unstructured = Unstructured::new(&buf);
18642 Self::arbitrary(&mut unstructured).unwrap_or_default()
18643 }
18644}
18645impl Default for MISSION_ACK_DATA {
18646 fn default() -> Self {
18647 Self::DEFAULT.clone()
18648 }
18649}
18650impl MessageData for MISSION_ACK_DATA {
18651 type Message = MavMessage;
18652 const ID: u32 = 47u32;
18653 const NAME: &'static str = "MISSION_ACK";
18654 const EXTRA_CRC: u8 = 153u8;
18655 const ENCODED_LEN: usize = 8usize;
18656 fn deser(
18657 _version: MavlinkVersion,
18658 __input: &[u8],
18659 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18660 let avail_len = __input.len();
18661 let mut payload_buf = [0; Self::ENCODED_LEN];
18662 let mut buf = if avail_len < Self::ENCODED_LEN {
18663 payload_buf[0..avail_len].copy_from_slice(__input);
18664 Bytes::new(&payload_buf)
18665 } else {
18666 Bytes::new(__input)
18667 };
18668 let mut __struct = Self::default();
18669 __struct.target_system = buf.get_u8();
18670 __struct.target_component = buf.get_u8();
18671 let tmp = buf.get_u8();
18672 __struct.mavtype =
18673 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18674 enum_type: "MavMissionResult",
18675 value: tmp as u32,
18676 })?;
18677 let tmp = buf.get_u8();
18678 __struct.mission_type =
18679 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18680 enum_type: "MavMissionType",
18681 value: tmp as u32,
18682 })?;
18683 __struct.opaque_id = buf.get_u32_le();
18684 Ok(__struct)
18685 }
18686 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18687 let mut __tmp = BytesMut::new(bytes);
18688 #[allow(clippy::absurd_extreme_comparisons)]
18689 #[allow(unused_comparisons)]
18690 if __tmp.remaining() < Self::ENCODED_LEN {
18691 panic!(
18692 "buffer is too small (need {} bytes, but got {})",
18693 Self::ENCODED_LEN,
18694 __tmp.remaining(),
18695 )
18696 }
18697 __tmp.put_u8(self.target_system);
18698 __tmp.put_u8(self.target_component);
18699 __tmp.put_u8(self.mavtype as u8);
18700 __tmp.put_u8(self.mission_type as u8);
18701 __tmp.put_u32_le(self.opaque_id);
18702 if matches!(version, MavlinkVersion::V2) {
18703 let len = __tmp.len();
18704 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18705 } else {
18706 __tmp.len()
18707 }
18708 }
18709}
18710#[doc = "id: 45"]
18711#[doc = "Delete all mission items at once."]
18712#[derive(Debug, Clone, PartialEq)]
18713#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18714#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18715pub struct MISSION_CLEAR_ALL_DATA {
18716 #[doc = "System ID"]
18717 pub target_system: u8,
18718 #[doc = "Component ID"]
18719 pub target_component: u8,
18720 #[doc = "Mission type."]
18721 #[cfg_attr(feature = "serde", serde(default))]
18722 pub mission_type: MavMissionType,
18723}
18724impl MISSION_CLEAR_ALL_DATA {
18725 pub const ENCODED_LEN: usize = 3usize;
18726 pub const DEFAULT: Self = Self {
18727 target_system: 0_u8,
18728 target_component: 0_u8,
18729 mission_type: MavMissionType::DEFAULT,
18730 };
18731 #[cfg(feature = "arbitrary")]
18732 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18733 use arbitrary::{Arbitrary, Unstructured};
18734 let mut buf = [0u8; 1024];
18735 rng.fill_bytes(&mut buf);
18736 let mut unstructured = Unstructured::new(&buf);
18737 Self::arbitrary(&mut unstructured).unwrap_or_default()
18738 }
18739}
18740impl Default for MISSION_CLEAR_ALL_DATA {
18741 fn default() -> Self {
18742 Self::DEFAULT.clone()
18743 }
18744}
18745impl MessageData for MISSION_CLEAR_ALL_DATA {
18746 type Message = MavMessage;
18747 const ID: u32 = 45u32;
18748 const NAME: &'static str = "MISSION_CLEAR_ALL";
18749 const EXTRA_CRC: u8 = 232u8;
18750 const ENCODED_LEN: usize = 3usize;
18751 fn deser(
18752 _version: MavlinkVersion,
18753 __input: &[u8],
18754 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18755 let avail_len = __input.len();
18756 let mut payload_buf = [0; Self::ENCODED_LEN];
18757 let mut buf = if avail_len < Self::ENCODED_LEN {
18758 payload_buf[0..avail_len].copy_from_slice(__input);
18759 Bytes::new(&payload_buf)
18760 } else {
18761 Bytes::new(__input)
18762 };
18763 let mut __struct = Self::default();
18764 __struct.target_system = buf.get_u8();
18765 __struct.target_component = buf.get_u8();
18766 let tmp = buf.get_u8();
18767 __struct.mission_type =
18768 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18769 enum_type: "MavMissionType",
18770 value: tmp as u32,
18771 })?;
18772 Ok(__struct)
18773 }
18774 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18775 let mut __tmp = BytesMut::new(bytes);
18776 #[allow(clippy::absurd_extreme_comparisons)]
18777 #[allow(unused_comparisons)]
18778 if __tmp.remaining() < Self::ENCODED_LEN {
18779 panic!(
18780 "buffer is too small (need {} bytes, but got {})",
18781 Self::ENCODED_LEN,
18782 __tmp.remaining(),
18783 )
18784 }
18785 __tmp.put_u8(self.target_system);
18786 __tmp.put_u8(self.target_component);
18787 __tmp.put_u8(self.mission_type as u8);
18788 if matches!(version, MavlinkVersion::V2) {
18789 let len = __tmp.len();
18790 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18791 } else {
18792 __tmp.len()
18793 }
18794 }
18795}
18796#[doc = "id: 44"]
18797#[doc = "This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of waypoints."]
18798#[derive(Debug, Clone, PartialEq)]
18799#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18800#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18801pub struct MISSION_COUNT_DATA {
18802 #[doc = "Number of mission items in the sequence"]
18803 pub count: u16,
18804 #[doc = "System ID"]
18805 pub target_system: u8,
18806 #[doc = "Component ID"]
18807 pub target_component: u8,
18808 #[doc = "Mission type."]
18809 #[cfg_attr(feature = "serde", serde(default))]
18810 pub mission_type: MavMissionType,
18811 #[doc = "Id of current on-vehicle mission, fence, or rally point plan (on download from vehicle). This field is used when downloading a plan from a vehicle to a GCS. 0 on upload to the vehicle from GCS. 0 if plan ids are not supported. The current on-vehicle plan ids are streamed in `MISSION_CURRENT`, allowing a GCS to determine if any part of the plan has changed and needs to be re-uploaded. The ids are recalculated by the vehicle when any part of the on-vehicle plan changes (when a new plan is uploaded, the vehicle returns the new id to the GCS in MISSION_ACK)."]
18812 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18813 pub opaque_id: u32,
18814}
18815impl MISSION_COUNT_DATA {
18816 pub const ENCODED_LEN: usize = 9usize;
18817 pub const DEFAULT: Self = Self {
18818 count: 0_u16,
18819 target_system: 0_u8,
18820 target_component: 0_u8,
18821 mission_type: MavMissionType::DEFAULT,
18822 opaque_id: 0_u32,
18823 };
18824 #[cfg(feature = "arbitrary")]
18825 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18826 use arbitrary::{Arbitrary, Unstructured};
18827 let mut buf = [0u8; 1024];
18828 rng.fill_bytes(&mut buf);
18829 let mut unstructured = Unstructured::new(&buf);
18830 Self::arbitrary(&mut unstructured).unwrap_or_default()
18831 }
18832}
18833impl Default for MISSION_COUNT_DATA {
18834 fn default() -> Self {
18835 Self::DEFAULT.clone()
18836 }
18837}
18838impl MessageData for MISSION_COUNT_DATA {
18839 type Message = MavMessage;
18840 const ID: u32 = 44u32;
18841 const NAME: &'static str = "MISSION_COUNT";
18842 const EXTRA_CRC: u8 = 221u8;
18843 const ENCODED_LEN: usize = 9usize;
18844 fn deser(
18845 _version: MavlinkVersion,
18846 __input: &[u8],
18847 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18848 let avail_len = __input.len();
18849 let mut payload_buf = [0; Self::ENCODED_LEN];
18850 let mut buf = if avail_len < Self::ENCODED_LEN {
18851 payload_buf[0..avail_len].copy_from_slice(__input);
18852 Bytes::new(&payload_buf)
18853 } else {
18854 Bytes::new(__input)
18855 };
18856 let mut __struct = Self::default();
18857 __struct.count = buf.get_u16_le();
18858 __struct.target_system = buf.get_u8();
18859 __struct.target_component = buf.get_u8();
18860 let tmp = buf.get_u8();
18861 __struct.mission_type =
18862 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18863 enum_type: "MavMissionType",
18864 value: tmp as u32,
18865 })?;
18866 __struct.opaque_id = buf.get_u32_le();
18867 Ok(__struct)
18868 }
18869 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18870 let mut __tmp = BytesMut::new(bytes);
18871 #[allow(clippy::absurd_extreme_comparisons)]
18872 #[allow(unused_comparisons)]
18873 if __tmp.remaining() < Self::ENCODED_LEN {
18874 panic!(
18875 "buffer is too small (need {} bytes, but got {})",
18876 Self::ENCODED_LEN,
18877 __tmp.remaining(),
18878 )
18879 }
18880 __tmp.put_u16_le(self.count);
18881 __tmp.put_u8(self.target_system);
18882 __tmp.put_u8(self.target_component);
18883 __tmp.put_u8(self.mission_type as u8);
18884 __tmp.put_u32_le(self.opaque_id);
18885 if matches!(version, MavlinkVersion::V2) {
18886 let len = __tmp.len();
18887 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18888 } else {
18889 __tmp.len()
18890 }
18891 }
18892}
18893#[doc = "id: 42"]
18894#[doc = "Message that announces the sequence number of the current target mission item (that the system will fly towards/execute when the mission is running). This message should be streamed all the time (nominally at 1Hz). This message should be emitted following a call to MAV_CMD_DO_SET_MISSION_CURRENT or MISSION_SET_CURRENT."]
18895#[derive(Debug, Clone, PartialEq)]
18896#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18897#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18898pub struct MISSION_CURRENT_DATA {
18899 #[doc = "Sequence"]
18900 pub seq: u16,
18901 #[doc = "Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle."]
18902 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18903 pub total: u16,
18904 #[doc = "Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported."]
18905 #[cfg_attr(feature = "serde", serde(default))]
18906 pub mission_state: MissionState,
18907 #[doc = "Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode)."]
18908 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18909 pub mission_mode: u8,
18910 #[doc = "Id of current on-vehicle mission plan, or 0 if IDs are not supported or there is no mission loaded. GCS can use this to track changes to the mission plan type. The same value is returned on mission upload (in the MISSION_ACK)."]
18911 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18912 pub mission_id: u32,
18913 #[doc = "Id of current on-vehicle fence plan, or 0 if IDs are not supported or there is no fence loaded. GCS can use this to track changes to the fence plan type. The same value is returned on fence upload (in the MISSION_ACK)."]
18914 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18915 pub fence_id: u32,
18916 #[doc = "Id of current on-vehicle rally point plan, or 0 if IDs are not supported or there are no rally points loaded. GCS can use this to track changes to the rally point plan type. The same value is returned on rally point upload (in the MISSION_ACK)."]
18917 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18918 pub rally_points_id: u32,
18919}
18920impl MISSION_CURRENT_DATA {
18921 pub const ENCODED_LEN: usize = 18usize;
18922 pub const DEFAULT: Self = Self {
18923 seq: 0_u16,
18924 total: 0_u16,
18925 mission_state: MissionState::DEFAULT,
18926 mission_mode: 0_u8,
18927 mission_id: 0_u32,
18928 fence_id: 0_u32,
18929 rally_points_id: 0_u32,
18930 };
18931 #[cfg(feature = "arbitrary")]
18932 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18933 use arbitrary::{Arbitrary, Unstructured};
18934 let mut buf = [0u8; 1024];
18935 rng.fill_bytes(&mut buf);
18936 let mut unstructured = Unstructured::new(&buf);
18937 Self::arbitrary(&mut unstructured).unwrap_or_default()
18938 }
18939}
18940impl Default for MISSION_CURRENT_DATA {
18941 fn default() -> Self {
18942 Self::DEFAULT.clone()
18943 }
18944}
18945impl MessageData for MISSION_CURRENT_DATA {
18946 type Message = MavMessage;
18947 const ID: u32 = 42u32;
18948 const NAME: &'static str = "MISSION_CURRENT";
18949 const EXTRA_CRC: u8 = 28u8;
18950 const ENCODED_LEN: usize = 18usize;
18951 fn deser(
18952 _version: MavlinkVersion,
18953 __input: &[u8],
18954 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18955 let avail_len = __input.len();
18956 let mut payload_buf = [0; Self::ENCODED_LEN];
18957 let mut buf = if avail_len < Self::ENCODED_LEN {
18958 payload_buf[0..avail_len].copy_from_slice(__input);
18959 Bytes::new(&payload_buf)
18960 } else {
18961 Bytes::new(__input)
18962 };
18963 let mut __struct = Self::default();
18964 __struct.seq = buf.get_u16_le();
18965 __struct.total = buf.get_u16_le();
18966 let tmp = buf.get_u8();
18967 __struct.mission_state =
18968 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18969 enum_type: "MissionState",
18970 value: tmp as u32,
18971 })?;
18972 __struct.mission_mode = buf.get_u8();
18973 __struct.mission_id = buf.get_u32_le();
18974 __struct.fence_id = buf.get_u32_le();
18975 __struct.rally_points_id = buf.get_u32_le();
18976 Ok(__struct)
18977 }
18978 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18979 let mut __tmp = BytesMut::new(bytes);
18980 #[allow(clippy::absurd_extreme_comparisons)]
18981 #[allow(unused_comparisons)]
18982 if __tmp.remaining() < Self::ENCODED_LEN {
18983 panic!(
18984 "buffer is too small (need {} bytes, but got {})",
18985 Self::ENCODED_LEN,
18986 __tmp.remaining(),
18987 )
18988 }
18989 __tmp.put_u16_le(self.seq);
18990 __tmp.put_u16_le(self.total);
18991 __tmp.put_u8(self.mission_state as u8);
18992 __tmp.put_u8(self.mission_mode);
18993 __tmp.put_u32_le(self.mission_id);
18994 __tmp.put_u32_le(self.fence_id);
18995 __tmp.put_u32_le(self.rally_points_id);
18996 if matches!(version, MavlinkVersion::V2) {
18997 let len = __tmp.len();
18998 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18999 } else {
19000 __tmp.len()
19001 }
19002 }
19003}
19004#[doc = "id: 39"]
19005#[doc = "Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN may be used to indicate an optional/default value (e.g. to use the system's current latitude or yaw rather than a specific value). See also <https://mavlink.io/en/services/mission.html>."]
19006#[derive(Debug, Clone, PartialEq)]
19007#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19008#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19009pub struct MISSION_ITEM_DATA {
19010 #[doc = "PARAM1, see MAV_CMD enum"]
19011 pub param1: f32,
19012 #[doc = "PARAM2, see MAV_CMD enum"]
19013 pub param2: f32,
19014 #[doc = "PARAM3, see MAV_CMD enum"]
19015 pub param3: f32,
19016 #[doc = "PARAM4, see MAV_CMD enum"]
19017 pub param4: f32,
19018 #[doc = "PARAM5 / local: X coordinate, global: latitude"]
19019 pub x: f32,
19020 #[doc = "PARAM6 / local: Y coordinate, global: longitude"]
19021 pub y: f32,
19022 #[doc = "PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame)."]
19023 pub z: f32,
19024 #[doc = "Sequence"]
19025 pub seq: u16,
19026 #[doc = "The scheduled action for the waypoint."]
19027 pub command: MavCmd,
19028 #[doc = "System ID"]
19029 pub target_system: u8,
19030 #[doc = "Component ID"]
19031 pub target_component: u8,
19032 #[doc = "The coordinate system of the waypoint."]
19033 pub frame: MavFrame,
19034 #[doc = "false:0, true:1"]
19035 pub current: u8,
19036 #[doc = "Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes."]
19037 pub autocontinue: u8,
19038 #[doc = "Mission type."]
19039 #[cfg_attr(feature = "serde", serde(default))]
19040 pub mission_type: MavMissionType,
19041}
19042impl MISSION_ITEM_DATA {
19043 pub const ENCODED_LEN: usize = 38usize;
19044 pub const DEFAULT: Self = Self {
19045 param1: 0.0_f32,
19046 param2: 0.0_f32,
19047 param3: 0.0_f32,
19048 param4: 0.0_f32,
19049 x: 0.0_f32,
19050 y: 0.0_f32,
19051 z: 0.0_f32,
19052 seq: 0_u16,
19053 command: MavCmd::DEFAULT,
19054 target_system: 0_u8,
19055 target_component: 0_u8,
19056 frame: MavFrame::DEFAULT,
19057 current: 0_u8,
19058 autocontinue: 0_u8,
19059 mission_type: MavMissionType::DEFAULT,
19060 };
19061 #[cfg(feature = "arbitrary")]
19062 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19063 use arbitrary::{Arbitrary, Unstructured};
19064 let mut buf = [0u8; 1024];
19065 rng.fill_bytes(&mut buf);
19066 let mut unstructured = Unstructured::new(&buf);
19067 Self::arbitrary(&mut unstructured).unwrap_or_default()
19068 }
19069}
19070impl Default for MISSION_ITEM_DATA {
19071 fn default() -> Self {
19072 Self::DEFAULT.clone()
19073 }
19074}
19075impl MessageData for MISSION_ITEM_DATA {
19076 type Message = MavMessage;
19077 const ID: u32 = 39u32;
19078 const NAME: &'static str = "MISSION_ITEM";
19079 const EXTRA_CRC: u8 = 254u8;
19080 const ENCODED_LEN: usize = 38usize;
19081 fn deser(
19082 _version: MavlinkVersion,
19083 __input: &[u8],
19084 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19085 let avail_len = __input.len();
19086 let mut payload_buf = [0; Self::ENCODED_LEN];
19087 let mut buf = if avail_len < Self::ENCODED_LEN {
19088 payload_buf[0..avail_len].copy_from_slice(__input);
19089 Bytes::new(&payload_buf)
19090 } else {
19091 Bytes::new(__input)
19092 };
19093 let mut __struct = Self::default();
19094 __struct.param1 = buf.get_f32_le();
19095 __struct.param2 = buf.get_f32_le();
19096 __struct.param3 = buf.get_f32_le();
19097 __struct.param4 = buf.get_f32_le();
19098 __struct.x = buf.get_f32_le();
19099 __struct.y = buf.get_f32_le();
19100 __struct.z = buf.get_f32_le();
19101 __struct.seq = buf.get_u16_le();
19102 let tmp = buf.get_u16_le();
19103 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
19104 ::mavlink_core::error::ParserError::InvalidEnum {
19105 enum_type: "MavCmd",
19106 value: tmp as u32,
19107 },
19108 )?;
19109 __struct.target_system = buf.get_u8();
19110 __struct.target_component = buf.get_u8();
19111 let tmp = buf.get_u8();
19112 __struct.frame =
19113 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19114 enum_type: "MavFrame",
19115 value: tmp as u32,
19116 })?;
19117 __struct.current = buf.get_u8();
19118 __struct.autocontinue = buf.get_u8();
19119 let tmp = buf.get_u8();
19120 __struct.mission_type =
19121 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19122 enum_type: "MavMissionType",
19123 value: tmp as u32,
19124 })?;
19125 Ok(__struct)
19126 }
19127 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19128 let mut __tmp = BytesMut::new(bytes);
19129 #[allow(clippy::absurd_extreme_comparisons)]
19130 #[allow(unused_comparisons)]
19131 if __tmp.remaining() < Self::ENCODED_LEN {
19132 panic!(
19133 "buffer is too small (need {} bytes, but got {})",
19134 Self::ENCODED_LEN,
19135 __tmp.remaining(),
19136 )
19137 }
19138 __tmp.put_f32_le(self.param1);
19139 __tmp.put_f32_le(self.param2);
19140 __tmp.put_f32_le(self.param3);
19141 __tmp.put_f32_le(self.param4);
19142 __tmp.put_f32_le(self.x);
19143 __tmp.put_f32_le(self.y);
19144 __tmp.put_f32_le(self.z);
19145 __tmp.put_u16_le(self.seq);
19146 __tmp.put_u16_le(self.command as u16);
19147 __tmp.put_u8(self.target_system);
19148 __tmp.put_u8(self.target_component);
19149 __tmp.put_u8(self.frame as u8);
19150 __tmp.put_u8(self.current);
19151 __tmp.put_u8(self.autocontinue);
19152 __tmp.put_u8(self.mission_type as u8);
19153 if matches!(version, MavlinkVersion::V2) {
19154 let len = __tmp.len();
19155 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19156 } else {
19157 __tmp.len()
19158 }
19159 }
19160}
19161#[doc = "id: 73"]
19162#[doc = "Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). See also <https://mavlink.io/en/services/mission.html>."]
19163#[derive(Debug, Clone, PartialEq)]
19164#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19165#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19166pub struct MISSION_ITEM_INT_DATA {
19167 #[doc = "PARAM1, see MAV_CMD enum"]
19168 pub param1: f32,
19169 #[doc = "PARAM2, see MAV_CMD enum"]
19170 pub param2: f32,
19171 #[doc = "PARAM3, see MAV_CMD enum"]
19172 pub param3: f32,
19173 #[doc = "PARAM4, see MAV_CMD enum"]
19174 pub param4: f32,
19175 #[doc = "PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7"]
19176 pub x: i32,
19177 #[doc = "PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7"]
19178 pub y: i32,
19179 #[doc = "PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame."]
19180 pub z: f32,
19181 #[doc = "Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4)."]
19182 pub seq: u16,
19183 #[doc = "The scheduled action for the waypoint."]
19184 pub command: MavCmd,
19185 #[doc = "System ID"]
19186 pub target_system: u8,
19187 #[doc = "Component ID"]
19188 pub target_component: u8,
19189 #[doc = "The coordinate system of the waypoint."]
19190 pub frame: MavFrame,
19191 #[doc = "false:0, true:1"]
19192 pub current: u8,
19193 #[doc = "Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes."]
19194 pub autocontinue: u8,
19195 #[doc = "Mission type."]
19196 #[cfg_attr(feature = "serde", serde(default))]
19197 pub mission_type: MavMissionType,
19198}
19199impl MISSION_ITEM_INT_DATA {
19200 pub const ENCODED_LEN: usize = 38usize;
19201 pub const DEFAULT: Self = Self {
19202 param1: 0.0_f32,
19203 param2: 0.0_f32,
19204 param3: 0.0_f32,
19205 param4: 0.0_f32,
19206 x: 0_i32,
19207 y: 0_i32,
19208 z: 0.0_f32,
19209 seq: 0_u16,
19210 command: MavCmd::DEFAULT,
19211 target_system: 0_u8,
19212 target_component: 0_u8,
19213 frame: MavFrame::DEFAULT,
19214 current: 0_u8,
19215 autocontinue: 0_u8,
19216 mission_type: MavMissionType::DEFAULT,
19217 };
19218 #[cfg(feature = "arbitrary")]
19219 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19220 use arbitrary::{Arbitrary, Unstructured};
19221 let mut buf = [0u8; 1024];
19222 rng.fill_bytes(&mut buf);
19223 let mut unstructured = Unstructured::new(&buf);
19224 Self::arbitrary(&mut unstructured).unwrap_or_default()
19225 }
19226}
19227impl Default for MISSION_ITEM_INT_DATA {
19228 fn default() -> Self {
19229 Self::DEFAULT.clone()
19230 }
19231}
19232impl MessageData for MISSION_ITEM_INT_DATA {
19233 type Message = MavMessage;
19234 const ID: u32 = 73u32;
19235 const NAME: &'static str = "MISSION_ITEM_INT";
19236 const EXTRA_CRC: u8 = 38u8;
19237 const ENCODED_LEN: usize = 38usize;
19238 fn deser(
19239 _version: MavlinkVersion,
19240 __input: &[u8],
19241 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19242 let avail_len = __input.len();
19243 let mut payload_buf = [0; Self::ENCODED_LEN];
19244 let mut buf = if avail_len < Self::ENCODED_LEN {
19245 payload_buf[0..avail_len].copy_from_slice(__input);
19246 Bytes::new(&payload_buf)
19247 } else {
19248 Bytes::new(__input)
19249 };
19250 let mut __struct = Self::default();
19251 __struct.param1 = buf.get_f32_le();
19252 __struct.param2 = buf.get_f32_le();
19253 __struct.param3 = buf.get_f32_le();
19254 __struct.param4 = buf.get_f32_le();
19255 __struct.x = buf.get_i32_le();
19256 __struct.y = buf.get_i32_le();
19257 __struct.z = buf.get_f32_le();
19258 __struct.seq = buf.get_u16_le();
19259 let tmp = buf.get_u16_le();
19260 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
19261 ::mavlink_core::error::ParserError::InvalidEnum {
19262 enum_type: "MavCmd",
19263 value: tmp as u32,
19264 },
19265 )?;
19266 __struct.target_system = buf.get_u8();
19267 __struct.target_component = buf.get_u8();
19268 let tmp = buf.get_u8();
19269 __struct.frame =
19270 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19271 enum_type: "MavFrame",
19272 value: tmp as u32,
19273 })?;
19274 __struct.current = buf.get_u8();
19275 __struct.autocontinue = buf.get_u8();
19276 let tmp = buf.get_u8();
19277 __struct.mission_type =
19278 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19279 enum_type: "MavMissionType",
19280 value: tmp as u32,
19281 })?;
19282 Ok(__struct)
19283 }
19284 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19285 let mut __tmp = BytesMut::new(bytes);
19286 #[allow(clippy::absurd_extreme_comparisons)]
19287 #[allow(unused_comparisons)]
19288 if __tmp.remaining() < Self::ENCODED_LEN {
19289 panic!(
19290 "buffer is too small (need {} bytes, but got {})",
19291 Self::ENCODED_LEN,
19292 __tmp.remaining(),
19293 )
19294 }
19295 __tmp.put_f32_le(self.param1);
19296 __tmp.put_f32_le(self.param2);
19297 __tmp.put_f32_le(self.param3);
19298 __tmp.put_f32_le(self.param4);
19299 __tmp.put_i32_le(self.x);
19300 __tmp.put_i32_le(self.y);
19301 __tmp.put_f32_le(self.z);
19302 __tmp.put_u16_le(self.seq);
19303 __tmp.put_u16_le(self.command as u16);
19304 __tmp.put_u8(self.target_system);
19305 __tmp.put_u8(self.target_component);
19306 __tmp.put_u8(self.frame as u8);
19307 __tmp.put_u8(self.current);
19308 __tmp.put_u8(self.autocontinue);
19309 __tmp.put_u8(self.mission_type as u8);
19310 if matches!(version, MavlinkVersion::V2) {
19311 let len = __tmp.len();
19312 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19313 } else {
19314 __tmp.len()
19315 }
19316 }
19317}
19318#[doc = "id: 46"]
19319#[doc = "A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint."]
19320#[derive(Debug, Clone, PartialEq)]
19321#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19322#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19323pub struct MISSION_ITEM_REACHED_DATA {
19324 #[doc = "Sequence"]
19325 pub seq: u16,
19326}
19327impl MISSION_ITEM_REACHED_DATA {
19328 pub const ENCODED_LEN: usize = 2usize;
19329 pub const DEFAULT: Self = Self { seq: 0_u16 };
19330 #[cfg(feature = "arbitrary")]
19331 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19332 use arbitrary::{Arbitrary, Unstructured};
19333 let mut buf = [0u8; 1024];
19334 rng.fill_bytes(&mut buf);
19335 let mut unstructured = Unstructured::new(&buf);
19336 Self::arbitrary(&mut unstructured).unwrap_or_default()
19337 }
19338}
19339impl Default for MISSION_ITEM_REACHED_DATA {
19340 fn default() -> Self {
19341 Self::DEFAULT.clone()
19342 }
19343}
19344impl MessageData for MISSION_ITEM_REACHED_DATA {
19345 type Message = MavMessage;
19346 const ID: u32 = 46u32;
19347 const NAME: &'static str = "MISSION_ITEM_REACHED";
19348 const EXTRA_CRC: u8 = 11u8;
19349 const ENCODED_LEN: usize = 2usize;
19350 fn deser(
19351 _version: MavlinkVersion,
19352 __input: &[u8],
19353 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19354 let avail_len = __input.len();
19355 let mut payload_buf = [0; Self::ENCODED_LEN];
19356 let mut buf = if avail_len < Self::ENCODED_LEN {
19357 payload_buf[0..avail_len].copy_from_slice(__input);
19358 Bytes::new(&payload_buf)
19359 } else {
19360 Bytes::new(__input)
19361 };
19362 let mut __struct = Self::default();
19363 __struct.seq = buf.get_u16_le();
19364 Ok(__struct)
19365 }
19366 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19367 let mut __tmp = BytesMut::new(bytes);
19368 #[allow(clippy::absurd_extreme_comparisons)]
19369 #[allow(unused_comparisons)]
19370 if __tmp.remaining() < Self::ENCODED_LEN {
19371 panic!(
19372 "buffer is too small (need {} bytes, but got {})",
19373 Self::ENCODED_LEN,
19374 __tmp.remaining(),
19375 )
19376 }
19377 __tmp.put_u16_le(self.seq);
19378 if matches!(version, MavlinkVersion::V2) {
19379 let len = __tmp.len();
19380 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19381 } else {
19382 __tmp.len()
19383 }
19384 }
19385}
19386#[doc = "id: 40"]
19387#[doc = "Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. <https://mavlink.io/en/services/mission.html>."]
19388#[derive(Debug, Clone, PartialEq)]
19389#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19390#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19391pub struct MISSION_REQUEST_DATA {
19392 #[doc = "Sequence"]
19393 pub seq: u16,
19394 #[doc = "System ID"]
19395 pub target_system: u8,
19396 #[doc = "Component ID"]
19397 pub target_component: u8,
19398 #[doc = "Mission type."]
19399 #[cfg_attr(feature = "serde", serde(default))]
19400 pub mission_type: MavMissionType,
19401}
19402impl MISSION_REQUEST_DATA {
19403 pub const ENCODED_LEN: usize = 5usize;
19404 pub const DEFAULT: Self = Self {
19405 seq: 0_u16,
19406 target_system: 0_u8,
19407 target_component: 0_u8,
19408 mission_type: MavMissionType::DEFAULT,
19409 };
19410 #[cfg(feature = "arbitrary")]
19411 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19412 use arbitrary::{Arbitrary, Unstructured};
19413 let mut buf = [0u8; 1024];
19414 rng.fill_bytes(&mut buf);
19415 let mut unstructured = Unstructured::new(&buf);
19416 Self::arbitrary(&mut unstructured).unwrap_or_default()
19417 }
19418}
19419impl Default for MISSION_REQUEST_DATA {
19420 fn default() -> Self {
19421 Self::DEFAULT.clone()
19422 }
19423}
19424impl MessageData for MISSION_REQUEST_DATA {
19425 type Message = MavMessage;
19426 const ID: u32 = 40u32;
19427 const NAME: &'static str = "MISSION_REQUEST";
19428 const EXTRA_CRC: u8 = 230u8;
19429 const ENCODED_LEN: usize = 5usize;
19430 fn deser(
19431 _version: MavlinkVersion,
19432 __input: &[u8],
19433 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19434 let avail_len = __input.len();
19435 let mut payload_buf = [0; Self::ENCODED_LEN];
19436 let mut buf = if avail_len < Self::ENCODED_LEN {
19437 payload_buf[0..avail_len].copy_from_slice(__input);
19438 Bytes::new(&payload_buf)
19439 } else {
19440 Bytes::new(__input)
19441 };
19442 let mut __struct = Self::default();
19443 __struct.seq = buf.get_u16_le();
19444 __struct.target_system = buf.get_u8();
19445 __struct.target_component = buf.get_u8();
19446 let tmp = buf.get_u8();
19447 __struct.mission_type =
19448 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19449 enum_type: "MavMissionType",
19450 value: tmp as u32,
19451 })?;
19452 Ok(__struct)
19453 }
19454 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19455 let mut __tmp = BytesMut::new(bytes);
19456 #[allow(clippy::absurd_extreme_comparisons)]
19457 #[allow(unused_comparisons)]
19458 if __tmp.remaining() < Self::ENCODED_LEN {
19459 panic!(
19460 "buffer is too small (need {} bytes, but got {})",
19461 Self::ENCODED_LEN,
19462 __tmp.remaining(),
19463 )
19464 }
19465 __tmp.put_u16_le(self.seq);
19466 __tmp.put_u8(self.target_system);
19467 __tmp.put_u8(self.target_component);
19468 __tmp.put_u8(self.mission_type as u8);
19469 if matches!(version, MavlinkVersion::V2) {
19470 let len = __tmp.len();
19471 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19472 } else {
19473 __tmp.len()
19474 }
19475 }
19476}
19477#[doc = "id: 51"]
19478#[doc = "Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM_INT message. <https://mavlink.io/en/services/mission.html>."]
19479#[derive(Debug, Clone, PartialEq)]
19480#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19481#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19482pub struct MISSION_REQUEST_INT_DATA {
19483 #[doc = "Sequence"]
19484 pub seq: u16,
19485 #[doc = "System ID"]
19486 pub target_system: u8,
19487 #[doc = "Component ID"]
19488 pub target_component: u8,
19489 #[doc = "Mission type."]
19490 #[cfg_attr(feature = "serde", serde(default))]
19491 pub mission_type: MavMissionType,
19492}
19493impl MISSION_REQUEST_INT_DATA {
19494 pub const ENCODED_LEN: usize = 5usize;
19495 pub const DEFAULT: Self = Self {
19496 seq: 0_u16,
19497 target_system: 0_u8,
19498 target_component: 0_u8,
19499 mission_type: MavMissionType::DEFAULT,
19500 };
19501 #[cfg(feature = "arbitrary")]
19502 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19503 use arbitrary::{Arbitrary, Unstructured};
19504 let mut buf = [0u8; 1024];
19505 rng.fill_bytes(&mut buf);
19506 let mut unstructured = Unstructured::new(&buf);
19507 Self::arbitrary(&mut unstructured).unwrap_or_default()
19508 }
19509}
19510impl Default for MISSION_REQUEST_INT_DATA {
19511 fn default() -> Self {
19512 Self::DEFAULT.clone()
19513 }
19514}
19515impl MessageData for MISSION_REQUEST_INT_DATA {
19516 type Message = MavMessage;
19517 const ID: u32 = 51u32;
19518 const NAME: &'static str = "MISSION_REQUEST_INT";
19519 const EXTRA_CRC: u8 = 196u8;
19520 const ENCODED_LEN: usize = 5usize;
19521 fn deser(
19522 _version: MavlinkVersion,
19523 __input: &[u8],
19524 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19525 let avail_len = __input.len();
19526 let mut payload_buf = [0; Self::ENCODED_LEN];
19527 let mut buf = if avail_len < Self::ENCODED_LEN {
19528 payload_buf[0..avail_len].copy_from_slice(__input);
19529 Bytes::new(&payload_buf)
19530 } else {
19531 Bytes::new(__input)
19532 };
19533 let mut __struct = Self::default();
19534 __struct.seq = buf.get_u16_le();
19535 __struct.target_system = buf.get_u8();
19536 __struct.target_component = buf.get_u8();
19537 let tmp = buf.get_u8();
19538 __struct.mission_type =
19539 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19540 enum_type: "MavMissionType",
19541 value: tmp as u32,
19542 })?;
19543 Ok(__struct)
19544 }
19545 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19546 let mut __tmp = BytesMut::new(bytes);
19547 #[allow(clippy::absurd_extreme_comparisons)]
19548 #[allow(unused_comparisons)]
19549 if __tmp.remaining() < Self::ENCODED_LEN {
19550 panic!(
19551 "buffer is too small (need {} bytes, but got {})",
19552 Self::ENCODED_LEN,
19553 __tmp.remaining(),
19554 )
19555 }
19556 __tmp.put_u16_le(self.seq);
19557 __tmp.put_u8(self.target_system);
19558 __tmp.put_u8(self.target_component);
19559 __tmp.put_u8(self.mission_type as u8);
19560 if matches!(version, MavlinkVersion::V2) {
19561 let len = __tmp.len();
19562 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19563 } else {
19564 __tmp.len()
19565 }
19566 }
19567}
19568#[doc = "id: 43"]
19569#[doc = "Request the overall list of mission items from the system/component."]
19570#[derive(Debug, Clone, PartialEq)]
19571#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19572#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19573pub struct MISSION_REQUEST_LIST_DATA {
19574 #[doc = "System ID"]
19575 pub target_system: u8,
19576 #[doc = "Component ID"]
19577 pub target_component: u8,
19578 #[doc = "Mission type."]
19579 #[cfg_attr(feature = "serde", serde(default))]
19580 pub mission_type: MavMissionType,
19581}
19582impl MISSION_REQUEST_LIST_DATA {
19583 pub const ENCODED_LEN: usize = 3usize;
19584 pub const DEFAULT: Self = Self {
19585 target_system: 0_u8,
19586 target_component: 0_u8,
19587 mission_type: MavMissionType::DEFAULT,
19588 };
19589 #[cfg(feature = "arbitrary")]
19590 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19591 use arbitrary::{Arbitrary, Unstructured};
19592 let mut buf = [0u8; 1024];
19593 rng.fill_bytes(&mut buf);
19594 let mut unstructured = Unstructured::new(&buf);
19595 Self::arbitrary(&mut unstructured).unwrap_or_default()
19596 }
19597}
19598impl Default for MISSION_REQUEST_LIST_DATA {
19599 fn default() -> Self {
19600 Self::DEFAULT.clone()
19601 }
19602}
19603impl MessageData for MISSION_REQUEST_LIST_DATA {
19604 type Message = MavMessage;
19605 const ID: u32 = 43u32;
19606 const NAME: &'static str = "MISSION_REQUEST_LIST";
19607 const EXTRA_CRC: u8 = 132u8;
19608 const ENCODED_LEN: usize = 3usize;
19609 fn deser(
19610 _version: MavlinkVersion,
19611 __input: &[u8],
19612 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19613 let avail_len = __input.len();
19614 let mut payload_buf = [0; Self::ENCODED_LEN];
19615 let mut buf = if avail_len < Self::ENCODED_LEN {
19616 payload_buf[0..avail_len].copy_from_slice(__input);
19617 Bytes::new(&payload_buf)
19618 } else {
19619 Bytes::new(__input)
19620 };
19621 let mut __struct = Self::default();
19622 __struct.target_system = buf.get_u8();
19623 __struct.target_component = buf.get_u8();
19624 let tmp = buf.get_u8();
19625 __struct.mission_type =
19626 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19627 enum_type: "MavMissionType",
19628 value: tmp as u32,
19629 })?;
19630 Ok(__struct)
19631 }
19632 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19633 let mut __tmp = BytesMut::new(bytes);
19634 #[allow(clippy::absurd_extreme_comparisons)]
19635 #[allow(unused_comparisons)]
19636 if __tmp.remaining() < Self::ENCODED_LEN {
19637 panic!(
19638 "buffer is too small (need {} bytes, but got {})",
19639 Self::ENCODED_LEN,
19640 __tmp.remaining(),
19641 )
19642 }
19643 __tmp.put_u8(self.target_system);
19644 __tmp.put_u8(self.target_component);
19645 __tmp.put_u8(self.mission_type as u8);
19646 if matches!(version, MavlinkVersion::V2) {
19647 let len = __tmp.len();
19648 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19649 } else {
19650 __tmp.len()
19651 }
19652 }
19653}
19654#[doc = "id: 37"]
19655#[doc = "Request a partial list of mission items from the system/component. <https://mavlink.io/en/services/mission.html>. If start and end index are the same, just send one waypoint."]
19656#[derive(Debug, Clone, PartialEq)]
19657#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19658#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19659pub struct MISSION_REQUEST_PARTIAL_LIST_DATA {
19660 #[doc = "Start index"]
19661 pub start_index: i16,
19662 #[doc = "End index, -1 by default (-1: send list to end). Else a valid index of the list"]
19663 pub end_index: i16,
19664 #[doc = "System ID"]
19665 pub target_system: u8,
19666 #[doc = "Component ID"]
19667 pub target_component: u8,
19668 #[doc = "Mission type."]
19669 #[cfg_attr(feature = "serde", serde(default))]
19670 pub mission_type: MavMissionType,
19671}
19672impl MISSION_REQUEST_PARTIAL_LIST_DATA {
19673 pub const ENCODED_LEN: usize = 7usize;
19674 pub const DEFAULT: Self = Self {
19675 start_index: 0_i16,
19676 end_index: 0_i16,
19677 target_system: 0_u8,
19678 target_component: 0_u8,
19679 mission_type: MavMissionType::DEFAULT,
19680 };
19681 #[cfg(feature = "arbitrary")]
19682 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19683 use arbitrary::{Arbitrary, Unstructured};
19684 let mut buf = [0u8; 1024];
19685 rng.fill_bytes(&mut buf);
19686 let mut unstructured = Unstructured::new(&buf);
19687 Self::arbitrary(&mut unstructured).unwrap_or_default()
19688 }
19689}
19690impl Default for MISSION_REQUEST_PARTIAL_LIST_DATA {
19691 fn default() -> Self {
19692 Self::DEFAULT.clone()
19693 }
19694}
19695impl MessageData for MISSION_REQUEST_PARTIAL_LIST_DATA {
19696 type Message = MavMessage;
19697 const ID: u32 = 37u32;
19698 const NAME: &'static str = "MISSION_REQUEST_PARTIAL_LIST";
19699 const EXTRA_CRC: u8 = 212u8;
19700 const ENCODED_LEN: usize = 7usize;
19701 fn deser(
19702 _version: MavlinkVersion,
19703 __input: &[u8],
19704 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19705 let avail_len = __input.len();
19706 let mut payload_buf = [0; Self::ENCODED_LEN];
19707 let mut buf = if avail_len < Self::ENCODED_LEN {
19708 payload_buf[0..avail_len].copy_from_slice(__input);
19709 Bytes::new(&payload_buf)
19710 } else {
19711 Bytes::new(__input)
19712 };
19713 let mut __struct = Self::default();
19714 __struct.start_index = buf.get_i16_le();
19715 __struct.end_index = buf.get_i16_le();
19716 __struct.target_system = buf.get_u8();
19717 __struct.target_component = buf.get_u8();
19718 let tmp = buf.get_u8();
19719 __struct.mission_type =
19720 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19721 enum_type: "MavMissionType",
19722 value: tmp as u32,
19723 })?;
19724 Ok(__struct)
19725 }
19726 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19727 let mut __tmp = BytesMut::new(bytes);
19728 #[allow(clippy::absurd_extreme_comparisons)]
19729 #[allow(unused_comparisons)]
19730 if __tmp.remaining() < Self::ENCODED_LEN {
19731 panic!(
19732 "buffer is too small (need {} bytes, but got {})",
19733 Self::ENCODED_LEN,
19734 __tmp.remaining(),
19735 )
19736 }
19737 __tmp.put_i16_le(self.start_index);
19738 __tmp.put_i16_le(self.end_index);
19739 __tmp.put_u8(self.target_system);
19740 __tmp.put_u8(self.target_component);
19741 __tmp.put_u8(self.mission_type as u8);
19742 if matches!(version, MavlinkVersion::V2) {
19743 let len = __tmp.len();
19744 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19745 } else {
19746 __tmp.len()
19747 }
19748 }
19749}
19750#[doc = "id: 41"]
19751#[doc = "Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed). If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items. Note that mission jump repeat counters are not reset (see MAV_CMD_DO_JUMP param2). This message may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE. If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission. If the system is not in mission mode this message must not trigger a switch to mission mode."]
19752#[derive(Debug, Clone, PartialEq)]
19753#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19754#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19755pub struct MISSION_SET_CURRENT_DATA {
19756 #[doc = "Sequence"]
19757 pub seq: u16,
19758 #[doc = "System ID"]
19759 pub target_system: u8,
19760 #[doc = "Component ID"]
19761 pub target_component: u8,
19762}
19763impl MISSION_SET_CURRENT_DATA {
19764 pub const ENCODED_LEN: usize = 4usize;
19765 pub const DEFAULT: Self = Self {
19766 seq: 0_u16,
19767 target_system: 0_u8,
19768 target_component: 0_u8,
19769 };
19770 #[cfg(feature = "arbitrary")]
19771 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19772 use arbitrary::{Arbitrary, Unstructured};
19773 let mut buf = [0u8; 1024];
19774 rng.fill_bytes(&mut buf);
19775 let mut unstructured = Unstructured::new(&buf);
19776 Self::arbitrary(&mut unstructured).unwrap_or_default()
19777 }
19778}
19779impl Default for MISSION_SET_CURRENT_DATA {
19780 fn default() -> Self {
19781 Self::DEFAULT.clone()
19782 }
19783}
19784impl MessageData for MISSION_SET_CURRENT_DATA {
19785 type Message = MavMessage;
19786 const ID: u32 = 41u32;
19787 const NAME: &'static str = "MISSION_SET_CURRENT";
19788 const EXTRA_CRC: u8 = 28u8;
19789 const ENCODED_LEN: usize = 4usize;
19790 fn deser(
19791 _version: MavlinkVersion,
19792 __input: &[u8],
19793 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19794 let avail_len = __input.len();
19795 let mut payload_buf = [0; Self::ENCODED_LEN];
19796 let mut buf = if avail_len < Self::ENCODED_LEN {
19797 payload_buf[0..avail_len].copy_from_slice(__input);
19798 Bytes::new(&payload_buf)
19799 } else {
19800 Bytes::new(__input)
19801 };
19802 let mut __struct = Self::default();
19803 __struct.seq = buf.get_u16_le();
19804 __struct.target_system = buf.get_u8();
19805 __struct.target_component = buf.get_u8();
19806 Ok(__struct)
19807 }
19808 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19809 let mut __tmp = BytesMut::new(bytes);
19810 #[allow(clippy::absurd_extreme_comparisons)]
19811 #[allow(unused_comparisons)]
19812 if __tmp.remaining() < Self::ENCODED_LEN {
19813 panic!(
19814 "buffer is too small (need {} bytes, but got {})",
19815 Self::ENCODED_LEN,
19816 __tmp.remaining(),
19817 )
19818 }
19819 __tmp.put_u16_le(self.seq);
19820 __tmp.put_u8(self.target_system);
19821 __tmp.put_u8(self.target_component);
19822 if matches!(version, MavlinkVersion::V2) {
19823 let len = __tmp.len();
19824 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19825 } else {
19826 __tmp.len()
19827 }
19828 }
19829}
19830#[doc = "id: 38"]
19831#[doc = "This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED!."]
19832#[derive(Debug, Clone, PartialEq)]
19833#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19834#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19835pub struct MISSION_WRITE_PARTIAL_LIST_DATA {
19836 #[doc = "Start index. Must be smaller / equal to the largest index of the current onboard list."]
19837 pub start_index: i16,
19838 #[doc = "End index, equal or greater than start index."]
19839 pub end_index: i16,
19840 #[doc = "System ID"]
19841 pub target_system: u8,
19842 #[doc = "Component ID"]
19843 pub target_component: u8,
19844 #[doc = "Mission type."]
19845 #[cfg_attr(feature = "serde", serde(default))]
19846 pub mission_type: MavMissionType,
19847}
19848impl MISSION_WRITE_PARTIAL_LIST_DATA {
19849 pub const ENCODED_LEN: usize = 7usize;
19850 pub const DEFAULT: Self = Self {
19851 start_index: 0_i16,
19852 end_index: 0_i16,
19853 target_system: 0_u8,
19854 target_component: 0_u8,
19855 mission_type: MavMissionType::DEFAULT,
19856 };
19857 #[cfg(feature = "arbitrary")]
19858 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19859 use arbitrary::{Arbitrary, Unstructured};
19860 let mut buf = [0u8; 1024];
19861 rng.fill_bytes(&mut buf);
19862 let mut unstructured = Unstructured::new(&buf);
19863 Self::arbitrary(&mut unstructured).unwrap_or_default()
19864 }
19865}
19866impl Default for MISSION_WRITE_PARTIAL_LIST_DATA {
19867 fn default() -> Self {
19868 Self::DEFAULT.clone()
19869 }
19870}
19871impl MessageData for MISSION_WRITE_PARTIAL_LIST_DATA {
19872 type Message = MavMessage;
19873 const ID: u32 = 38u32;
19874 const NAME: &'static str = "MISSION_WRITE_PARTIAL_LIST";
19875 const EXTRA_CRC: u8 = 9u8;
19876 const ENCODED_LEN: usize = 7usize;
19877 fn deser(
19878 _version: MavlinkVersion,
19879 __input: &[u8],
19880 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19881 let avail_len = __input.len();
19882 let mut payload_buf = [0; Self::ENCODED_LEN];
19883 let mut buf = if avail_len < Self::ENCODED_LEN {
19884 payload_buf[0..avail_len].copy_from_slice(__input);
19885 Bytes::new(&payload_buf)
19886 } else {
19887 Bytes::new(__input)
19888 };
19889 let mut __struct = Self::default();
19890 __struct.start_index = buf.get_i16_le();
19891 __struct.end_index = buf.get_i16_le();
19892 __struct.target_system = buf.get_u8();
19893 __struct.target_component = buf.get_u8();
19894 let tmp = buf.get_u8();
19895 __struct.mission_type =
19896 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19897 enum_type: "MavMissionType",
19898 value: tmp as u32,
19899 })?;
19900 Ok(__struct)
19901 }
19902 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19903 let mut __tmp = BytesMut::new(bytes);
19904 #[allow(clippy::absurd_extreme_comparisons)]
19905 #[allow(unused_comparisons)]
19906 if __tmp.remaining() < Self::ENCODED_LEN {
19907 panic!(
19908 "buffer is too small (need {} bytes, but got {})",
19909 Self::ENCODED_LEN,
19910 __tmp.remaining(),
19911 )
19912 }
19913 __tmp.put_i16_le(self.start_index);
19914 __tmp.put_i16_le(self.end_index);
19915 __tmp.put_u8(self.target_system);
19916 __tmp.put_u8(self.target_component);
19917 __tmp.put_u8(self.mission_type as u8);
19918 if matches!(version, MavlinkVersion::V2) {
19919 let len = __tmp.len();
19920 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19921 } else {
19922 __tmp.len()
19923 }
19924 }
19925}
19926#[doc = "id: 265"]
19927#[doc = "Orientation of a mount."]
19928#[derive(Debug, Clone, PartialEq)]
19929#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19930#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19931pub struct MOUNT_ORIENTATION_DATA {
19932 #[doc = "Timestamp (time since system boot)."]
19933 pub time_boot_ms: u32,
19934 #[doc = "Roll in global frame (set to NaN for invalid)."]
19935 pub roll: f32,
19936 #[doc = "Pitch in global frame (set to NaN for invalid)."]
19937 pub pitch: f32,
19938 #[doc = "Yaw relative to vehicle (set to NaN for invalid)."]
19939 pub yaw: f32,
19940 #[doc = "Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid)."]
19941 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19942 pub yaw_absolute: f32,
19943}
19944impl MOUNT_ORIENTATION_DATA {
19945 pub const ENCODED_LEN: usize = 20usize;
19946 pub const DEFAULT: Self = Self {
19947 time_boot_ms: 0_u32,
19948 roll: 0.0_f32,
19949 pitch: 0.0_f32,
19950 yaw: 0.0_f32,
19951 yaw_absolute: 0.0_f32,
19952 };
19953 #[cfg(feature = "arbitrary")]
19954 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19955 use arbitrary::{Arbitrary, Unstructured};
19956 let mut buf = [0u8; 1024];
19957 rng.fill_bytes(&mut buf);
19958 let mut unstructured = Unstructured::new(&buf);
19959 Self::arbitrary(&mut unstructured).unwrap_or_default()
19960 }
19961}
19962impl Default for MOUNT_ORIENTATION_DATA {
19963 fn default() -> Self {
19964 Self::DEFAULT.clone()
19965 }
19966}
19967impl MessageData for MOUNT_ORIENTATION_DATA {
19968 type Message = MavMessage;
19969 const ID: u32 = 265u32;
19970 const NAME: &'static str = "MOUNT_ORIENTATION";
19971 const EXTRA_CRC: u8 = 26u8;
19972 const ENCODED_LEN: usize = 20usize;
19973 fn deser(
19974 _version: MavlinkVersion,
19975 __input: &[u8],
19976 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19977 let avail_len = __input.len();
19978 let mut payload_buf = [0; Self::ENCODED_LEN];
19979 let mut buf = if avail_len < Self::ENCODED_LEN {
19980 payload_buf[0..avail_len].copy_from_slice(__input);
19981 Bytes::new(&payload_buf)
19982 } else {
19983 Bytes::new(__input)
19984 };
19985 let mut __struct = Self::default();
19986 __struct.time_boot_ms = buf.get_u32_le();
19987 __struct.roll = buf.get_f32_le();
19988 __struct.pitch = buf.get_f32_le();
19989 __struct.yaw = buf.get_f32_le();
19990 __struct.yaw_absolute = buf.get_f32_le();
19991 Ok(__struct)
19992 }
19993 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19994 let mut __tmp = BytesMut::new(bytes);
19995 #[allow(clippy::absurd_extreme_comparisons)]
19996 #[allow(unused_comparisons)]
19997 if __tmp.remaining() < Self::ENCODED_LEN {
19998 panic!(
19999 "buffer is too small (need {} bytes, but got {})",
20000 Self::ENCODED_LEN,
20001 __tmp.remaining(),
20002 )
20003 }
20004 __tmp.put_u32_le(self.time_boot_ms);
20005 __tmp.put_f32_le(self.roll);
20006 __tmp.put_f32_le(self.pitch);
20007 __tmp.put_f32_le(self.yaw);
20008 __tmp.put_f32_le(self.yaw_absolute);
20009 if matches!(version, MavlinkVersion::V2) {
20010 let len = __tmp.len();
20011 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20012 } else {
20013 __tmp.len()
20014 }
20015 }
20016}
20017#[doc = "id: 251"]
20018#[doc = "Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output."]
20019#[derive(Debug, Clone, PartialEq)]
20020#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20021#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20022pub struct NAMED_VALUE_FLOAT_DATA {
20023 #[doc = "Timestamp (time since system boot)."]
20024 pub time_boot_ms: u32,
20025 #[doc = "Floating point value"]
20026 pub value: f32,
20027 #[doc = "Name of the debug variable"]
20028 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20029 pub name: [u8; 10],
20030}
20031impl NAMED_VALUE_FLOAT_DATA {
20032 pub const ENCODED_LEN: usize = 18usize;
20033 pub const DEFAULT: Self = Self {
20034 time_boot_ms: 0_u32,
20035 value: 0.0_f32,
20036 name: [0_u8; 10usize],
20037 };
20038 #[cfg(feature = "arbitrary")]
20039 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20040 use arbitrary::{Arbitrary, Unstructured};
20041 let mut buf = [0u8; 1024];
20042 rng.fill_bytes(&mut buf);
20043 let mut unstructured = Unstructured::new(&buf);
20044 Self::arbitrary(&mut unstructured).unwrap_or_default()
20045 }
20046}
20047impl Default for NAMED_VALUE_FLOAT_DATA {
20048 fn default() -> Self {
20049 Self::DEFAULT.clone()
20050 }
20051}
20052impl MessageData for NAMED_VALUE_FLOAT_DATA {
20053 type Message = MavMessage;
20054 const ID: u32 = 251u32;
20055 const NAME: &'static str = "NAMED_VALUE_FLOAT";
20056 const EXTRA_CRC: u8 = 170u8;
20057 const ENCODED_LEN: usize = 18usize;
20058 fn deser(
20059 _version: MavlinkVersion,
20060 __input: &[u8],
20061 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20062 let avail_len = __input.len();
20063 let mut payload_buf = [0; Self::ENCODED_LEN];
20064 let mut buf = if avail_len < Self::ENCODED_LEN {
20065 payload_buf[0..avail_len].copy_from_slice(__input);
20066 Bytes::new(&payload_buf)
20067 } else {
20068 Bytes::new(__input)
20069 };
20070 let mut __struct = Self::default();
20071 __struct.time_boot_ms = buf.get_u32_le();
20072 __struct.value = buf.get_f32_le();
20073 for v in &mut __struct.name {
20074 let val = buf.get_u8();
20075 *v = val;
20076 }
20077 Ok(__struct)
20078 }
20079 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20080 let mut __tmp = BytesMut::new(bytes);
20081 #[allow(clippy::absurd_extreme_comparisons)]
20082 #[allow(unused_comparisons)]
20083 if __tmp.remaining() < Self::ENCODED_LEN {
20084 panic!(
20085 "buffer is too small (need {} bytes, but got {})",
20086 Self::ENCODED_LEN,
20087 __tmp.remaining(),
20088 )
20089 }
20090 __tmp.put_u32_le(self.time_boot_ms);
20091 __tmp.put_f32_le(self.value);
20092 for val in &self.name {
20093 __tmp.put_u8(*val);
20094 }
20095 if matches!(version, MavlinkVersion::V2) {
20096 let len = __tmp.len();
20097 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20098 } else {
20099 __tmp.len()
20100 }
20101 }
20102}
20103#[doc = "id: 252"]
20104#[doc = "Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output."]
20105#[derive(Debug, Clone, PartialEq)]
20106#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20107#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20108pub struct NAMED_VALUE_INT_DATA {
20109 #[doc = "Timestamp (time since system boot)."]
20110 pub time_boot_ms: u32,
20111 #[doc = "Signed integer value"]
20112 pub value: i32,
20113 #[doc = "Name of the debug variable"]
20114 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20115 pub name: [u8; 10],
20116}
20117impl NAMED_VALUE_INT_DATA {
20118 pub const ENCODED_LEN: usize = 18usize;
20119 pub const DEFAULT: Self = Self {
20120 time_boot_ms: 0_u32,
20121 value: 0_i32,
20122 name: [0_u8; 10usize],
20123 };
20124 #[cfg(feature = "arbitrary")]
20125 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20126 use arbitrary::{Arbitrary, Unstructured};
20127 let mut buf = [0u8; 1024];
20128 rng.fill_bytes(&mut buf);
20129 let mut unstructured = Unstructured::new(&buf);
20130 Self::arbitrary(&mut unstructured).unwrap_or_default()
20131 }
20132}
20133impl Default for NAMED_VALUE_INT_DATA {
20134 fn default() -> Self {
20135 Self::DEFAULT.clone()
20136 }
20137}
20138impl MessageData for NAMED_VALUE_INT_DATA {
20139 type Message = MavMessage;
20140 const ID: u32 = 252u32;
20141 const NAME: &'static str = "NAMED_VALUE_INT";
20142 const EXTRA_CRC: u8 = 44u8;
20143 const ENCODED_LEN: usize = 18usize;
20144 fn deser(
20145 _version: MavlinkVersion,
20146 __input: &[u8],
20147 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20148 let avail_len = __input.len();
20149 let mut payload_buf = [0; Self::ENCODED_LEN];
20150 let mut buf = if avail_len < Self::ENCODED_LEN {
20151 payload_buf[0..avail_len].copy_from_slice(__input);
20152 Bytes::new(&payload_buf)
20153 } else {
20154 Bytes::new(__input)
20155 };
20156 let mut __struct = Self::default();
20157 __struct.time_boot_ms = buf.get_u32_le();
20158 __struct.value = buf.get_i32_le();
20159 for v in &mut __struct.name {
20160 let val = buf.get_u8();
20161 *v = val;
20162 }
20163 Ok(__struct)
20164 }
20165 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20166 let mut __tmp = BytesMut::new(bytes);
20167 #[allow(clippy::absurd_extreme_comparisons)]
20168 #[allow(unused_comparisons)]
20169 if __tmp.remaining() < Self::ENCODED_LEN {
20170 panic!(
20171 "buffer is too small (need {} bytes, but got {})",
20172 Self::ENCODED_LEN,
20173 __tmp.remaining(),
20174 )
20175 }
20176 __tmp.put_u32_le(self.time_boot_ms);
20177 __tmp.put_i32_le(self.value);
20178 for val in &self.name {
20179 __tmp.put_u8(*val);
20180 }
20181 if matches!(version, MavlinkVersion::V2) {
20182 let len = __tmp.len();
20183 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20184 } else {
20185 __tmp.len()
20186 }
20187 }
20188}
20189#[doc = "id: 62"]
20190#[doc = "The state of the navigation and position controller."]
20191#[derive(Debug, Clone, PartialEq)]
20192#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20193#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20194pub struct NAV_CONTROLLER_OUTPUT_DATA {
20195 #[doc = "Current desired roll"]
20196 pub nav_roll: f32,
20197 #[doc = "Current desired pitch"]
20198 pub nav_pitch: f32,
20199 #[doc = "Current altitude error"]
20200 pub alt_error: f32,
20201 #[doc = "Current airspeed error"]
20202 pub aspd_error: f32,
20203 #[doc = "Current crosstrack error on x-y plane"]
20204 pub xtrack_error: f32,
20205 #[doc = "Current desired heading"]
20206 pub nav_bearing: i16,
20207 #[doc = "Bearing to current waypoint/target"]
20208 pub target_bearing: i16,
20209 #[doc = "Distance to active waypoint"]
20210 pub wp_dist: u16,
20211}
20212impl NAV_CONTROLLER_OUTPUT_DATA {
20213 pub const ENCODED_LEN: usize = 26usize;
20214 pub const DEFAULT: Self = Self {
20215 nav_roll: 0.0_f32,
20216 nav_pitch: 0.0_f32,
20217 alt_error: 0.0_f32,
20218 aspd_error: 0.0_f32,
20219 xtrack_error: 0.0_f32,
20220 nav_bearing: 0_i16,
20221 target_bearing: 0_i16,
20222 wp_dist: 0_u16,
20223 };
20224 #[cfg(feature = "arbitrary")]
20225 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20226 use arbitrary::{Arbitrary, Unstructured};
20227 let mut buf = [0u8; 1024];
20228 rng.fill_bytes(&mut buf);
20229 let mut unstructured = Unstructured::new(&buf);
20230 Self::arbitrary(&mut unstructured).unwrap_or_default()
20231 }
20232}
20233impl Default for NAV_CONTROLLER_OUTPUT_DATA {
20234 fn default() -> Self {
20235 Self::DEFAULT.clone()
20236 }
20237}
20238impl MessageData for NAV_CONTROLLER_OUTPUT_DATA {
20239 type Message = MavMessage;
20240 const ID: u32 = 62u32;
20241 const NAME: &'static str = "NAV_CONTROLLER_OUTPUT";
20242 const EXTRA_CRC: u8 = 183u8;
20243 const ENCODED_LEN: usize = 26usize;
20244 fn deser(
20245 _version: MavlinkVersion,
20246 __input: &[u8],
20247 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20248 let avail_len = __input.len();
20249 let mut payload_buf = [0; Self::ENCODED_LEN];
20250 let mut buf = if avail_len < Self::ENCODED_LEN {
20251 payload_buf[0..avail_len].copy_from_slice(__input);
20252 Bytes::new(&payload_buf)
20253 } else {
20254 Bytes::new(__input)
20255 };
20256 let mut __struct = Self::default();
20257 __struct.nav_roll = buf.get_f32_le();
20258 __struct.nav_pitch = buf.get_f32_le();
20259 __struct.alt_error = buf.get_f32_le();
20260 __struct.aspd_error = buf.get_f32_le();
20261 __struct.xtrack_error = buf.get_f32_le();
20262 __struct.nav_bearing = buf.get_i16_le();
20263 __struct.target_bearing = buf.get_i16_le();
20264 __struct.wp_dist = buf.get_u16_le();
20265 Ok(__struct)
20266 }
20267 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20268 let mut __tmp = BytesMut::new(bytes);
20269 #[allow(clippy::absurd_extreme_comparisons)]
20270 #[allow(unused_comparisons)]
20271 if __tmp.remaining() < Self::ENCODED_LEN {
20272 panic!(
20273 "buffer is too small (need {} bytes, but got {})",
20274 Self::ENCODED_LEN,
20275 __tmp.remaining(),
20276 )
20277 }
20278 __tmp.put_f32_le(self.nav_roll);
20279 __tmp.put_f32_le(self.nav_pitch);
20280 __tmp.put_f32_le(self.alt_error);
20281 __tmp.put_f32_le(self.aspd_error);
20282 __tmp.put_f32_le(self.xtrack_error);
20283 __tmp.put_i16_le(self.nav_bearing);
20284 __tmp.put_i16_le(self.target_bearing);
20285 __tmp.put_u16_le(self.wp_dist);
20286 if matches!(version, MavlinkVersion::V2) {
20287 let len = __tmp.len();
20288 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20289 } else {
20290 __tmp.len()
20291 }
20292 }
20293}
20294#[doc = "id: 330"]
20295#[doc = "Obstacle distances in front of the sensor, starting from the left in increment degrees to the right."]
20296#[derive(Debug, Clone, PartialEq)]
20297#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20298#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20299pub struct OBSTACLE_DISTANCE_DATA {
20300 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
20301 pub time_usec: u64,
20302 #[doc = "Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm."]
20303 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20304 pub distances: [u16; 72],
20305 #[doc = "Minimum distance the sensor can measure."]
20306 pub min_distance: u16,
20307 #[doc = "Maximum distance the sensor can measure."]
20308 pub max_distance: u16,
20309 #[doc = "Class id of the distance sensor type."]
20310 pub sensor_type: MavDistanceSensor,
20311 #[doc = "Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero."]
20312 pub increment: u8,
20313 #[doc = "Angular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise."]
20314 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20315 pub increment_f: f32,
20316 #[doc = "Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise."]
20317 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20318 pub angle_offset: f32,
20319 #[doc = "Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned."]
20320 #[cfg_attr(feature = "serde", serde(default))]
20321 pub frame: MavFrame,
20322}
20323impl OBSTACLE_DISTANCE_DATA {
20324 pub const ENCODED_LEN: usize = 167usize;
20325 pub const DEFAULT: Self = Self {
20326 time_usec: 0_u64,
20327 distances: [0_u16; 72usize],
20328 min_distance: 0_u16,
20329 max_distance: 0_u16,
20330 sensor_type: MavDistanceSensor::DEFAULT,
20331 increment: 0_u8,
20332 increment_f: 0.0_f32,
20333 angle_offset: 0.0_f32,
20334 frame: MavFrame::DEFAULT,
20335 };
20336 #[cfg(feature = "arbitrary")]
20337 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20338 use arbitrary::{Arbitrary, Unstructured};
20339 let mut buf = [0u8; 1024];
20340 rng.fill_bytes(&mut buf);
20341 let mut unstructured = Unstructured::new(&buf);
20342 Self::arbitrary(&mut unstructured).unwrap_or_default()
20343 }
20344}
20345impl Default for OBSTACLE_DISTANCE_DATA {
20346 fn default() -> Self {
20347 Self::DEFAULT.clone()
20348 }
20349}
20350impl MessageData for OBSTACLE_DISTANCE_DATA {
20351 type Message = MavMessage;
20352 const ID: u32 = 330u32;
20353 const NAME: &'static str = "OBSTACLE_DISTANCE";
20354 const EXTRA_CRC: u8 = 23u8;
20355 const ENCODED_LEN: usize = 167usize;
20356 fn deser(
20357 _version: MavlinkVersion,
20358 __input: &[u8],
20359 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20360 let avail_len = __input.len();
20361 let mut payload_buf = [0; Self::ENCODED_LEN];
20362 let mut buf = if avail_len < Self::ENCODED_LEN {
20363 payload_buf[0..avail_len].copy_from_slice(__input);
20364 Bytes::new(&payload_buf)
20365 } else {
20366 Bytes::new(__input)
20367 };
20368 let mut __struct = Self::default();
20369 __struct.time_usec = buf.get_u64_le();
20370 for v in &mut __struct.distances {
20371 let val = buf.get_u16_le();
20372 *v = val;
20373 }
20374 __struct.min_distance = buf.get_u16_le();
20375 __struct.max_distance = buf.get_u16_le();
20376 let tmp = buf.get_u8();
20377 __struct.sensor_type =
20378 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
20379 enum_type: "MavDistanceSensor",
20380 value: tmp as u32,
20381 })?;
20382 __struct.increment = buf.get_u8();
20383 __struct.increment_f = buf.get_f32_le();
20384 __struct.angle_offset = buf.get_f32_le();
20385 let tmp = buf.get_u8();
20386 __struct.frame =
20387 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
20388 enum_type: "MavFrame",
20389 value: tmp as u32,
20390 })?;
20391 Ok(__struct)
20392 }
20393 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20394 let mut __tmp = BytesMut::new(bytes);
20395 #[allow(clippy::absurd_extreme_comparisons)]
20396 #[allow(unused_comparisons)]
20397 if __tmp.remaining() < Self::ENCODED_LEN {
20398 panic!(
20399 "buffer is too small (need {} bytes, but got {})",
20400 Self::ENCODED_LEN,
20401 __tmp.remaining(),
20402 )
20403 }
20404 __tmp.put_u64_le(self.time_usec);
20405 for val in &self.distances {
20406 __tmp.put_u16_le(*val);
20407 }
20408 __tmp.put_u16_le(self.min_distance);
20409 __tmp.put_u16_le(self.max_distance);
20410 __tmp.put_u8(self.sensor_type as u8);
20411 __tmp.put_u8(self.increment);
20412 __tmp.put_f32_le(self.increment_f);
20413 __tmp.put_f32_le(self.angle_offset);
20414 __tmp.put_u8(self.frame as u8);
20415 if matches!(version, MavlinkVersion::V2) {
20416 let len = __tmp.len();
20417 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20418 } else {
20419 __tmp.len()
20420 }
20421 }
20422}
20423#[doc = "id: 331"]
20424#[doc = "Odometry message to communicate odometry information with an external interface. Fits ROS REP 147 standard for aerial vehicles (<http://www.ros.org/reps/rep-0147.html>)."]
20425#[derive(Debug, Clone, PartialEq)]
20426#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20427#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20428pub struct ODOMETRY_DATA {
20429 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
20430 pub time_usec: u64,
20431 #[doc = "X Position"]
20432 pub x: f32,
20433 #[doc = "Y Position"]
20434 pub y: f32,
20435 #[doc = "Z Position"]
20436 pub z: f32,
20437 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)"]
20438 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20439 pub q: [f32; 4],
20440 #[doc = "X linear speed"]
20441 pub vx: f32,
20442 #[doc = "Y linear speed"]
20443 pub vy: f32,
20444 #[doc = "Z linear speed"]
20445 pub vz: f32,
20446 #[doc = "Roll angular speed"]
20447 pub rollspeed: f32,
20448 #[doc = "Pitch angular speed"]
20449 pub pitchspeed: f32,
20450 #[doc = "Yaw angular speed"]
20451 pub yawspeed: f32,
20452 #[doc = "Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
20453 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20454 pub pose_covariance: [f32; 21],
20455 #[doc = "Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
20456 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20457 pub velocity_covariance: [f32; 21],
20458 #[doc = "Coordinate frame of reference for the pose data."]
20459 pub frame_id: MavFrame,
20460 #[doc = "Coordinate frame of reference for the velocity in free space (twist) data."]
20461 pub child_frame_id: MavFrame,
20462 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
20463 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20464 pub reset_counter: u8,
20465 #[doc = "Type of estimator that is providing the odometry."]
20466 #[cfg_attr(feature = "serde", serde(default))]
20467 pub estimator_type: MavEstimatorType,
20468 #[doc = "Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality"]
20469 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20470 pub quality: i8,
20471}
20472impl ODOMETRY_DATA {
20473 pub const ENCODED_LEN: usize = 233usize;
20474 pub const DEFAULT: Self = Self {
20475 time_usec: 0_u64,
20476 x: 0.0_f32,
20477 y: 0.0_f32,
20478 z: 0.0_f32,
20479 q: [0.0_f32; 4usize],
20480 vx: 0.0_f32,
20481 vy: 0.0_f32,
20482 vz: 0.0_f32,
20483 rollspeed: 0.0_f32,
20484 pitchspeed: 0.0_f32,
20485 yawspeed: 0.0_f32,
20486 pose_covariance: [0.0_f32; 21usize],
20487 velocity_covariance: [0.0_f32; 21usize],
20488 frame_id: MavFrame::DEFAULT,
20489 child_frame_id: MavFrame::DEFAULT,
20490 reset_counter: 0_u8,
20491 estimator_type: MavEstimatorType::DEFAULT,
20492 quality: 0_i8,
20493 };
20494 #[cfg(feature = "arbitrary")]
20495 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20496 use arbitrary::{Arbitrary, Unstructured};
20497 let mut buf = [0u8; 1024];
20498 rng.fill_bytes(&mut buf);
20499 let mut unstructured = Unstructured::new(&buf);
20500 Self::arbitrary(&mut unstructured).unwrap_or_default()
20501 }
20502}
20503impl Default for ODOMETRY_DATA {
20504 fn default() -> Self {
20505 Self::DEFAULT.clone()
20506 }
20507}
20508impl MessageData for ODOMETRY_DATA {
20509 type Message = MavMessage;
20510 const ID: u32 = 331u32;
20511 const NAME: &'static str = "ODOMETRY";
20512 const EXTRA_CRC: u8 = 91u8;
20513 const ENCODED_LEN: usize = 233usize;
20514 fn deser(
20515 _version: MavlinkVersion,
20516 __input: &[u8],
20517 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20518 let avail_len = __input.len();
20519 let mut payload_buf = [0; Self::ENCODED_LEN];
20520 let mut buf = if avail_len < Self::ENCODED_LEN {
20521 payload_buf[0..avail_len].copy_from_slice(__input);
20522 Bytes::new(&payload_buf)
20523 } else {
20524 Bytes::new(__input)
20525 };
20526 let mut __struct = Self::default();
20527 __struct.time_usec = buf.get_u64_le();
20528 __struct.x = buf.get_f32_le();
20529 __struct.y = buf.get_f32_le();
20530 __struct.z = buf.get_f32_le();
20531 for v in &mut __struct.q {
20532 let val = buf.get_f32_le();
20533 *v = val;
20534 }
20535 __struct.vx = buf.get_f32_le();
20536 __struct.vy = buf.get_f32_le();
20537 __struct.vz = buf.get_f32_le();
20538 __struct.rollspeed = buf.get_f32_le();
20539 __struct.pitchspeed = buf.get_f32_le();
20540 __struct.yawspeed = buf.get_f32_le();
20541 for v in &mut __struct.pose_covariance {
20542 let val = buf.get_f32_le();
20543 *v = val;
20544 }
20545 for v in &mut __struct.velocity_covariance {
20546 let val = buf.get_f32_le();
20547 *v = val;
20548 }
20549 let tmp = buf.get_u8();
20550 __struct.frame_id =
20551 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
20552 enum_type: "MavFrame",
20553 value: tmp as u32,
20554 })?;
20555 let tmp = buf.get_u8();
20556 __struct.child_frame_id =
20557 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
20558 enum_type: "MavFrame",
20559 value: tmp as u32,
20560 })?;
20561 __struct.reset_counter = buf.get_u8();
20562 let tmp = buf.get_u8();
20563 __struct.estimator_type =
20564 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
20565 enum_type: "MavEstimatorType",
20566 value: tmp as u32,
20567 })?;
20568 __struct.quality = buf.get_i8();
20569 Ok(__struct)
20570 }
20571 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20572 let mut __tmp = BytesMut::new(bytes);
20573 #[allow(clippy::absurd_extreme_comparisons)]
20574 #[allow(unused_comparisons)]
20575 if __tmp.remaining() < Self::ENCODED_LEN {
20576 panic!(
20577 "buffer is too small (need {} bytes, but got {})",
20578 Self::ENCODED_LEN,
20579 __tmp.remaining(),
20580 )
20581 }
20582 __tmp.put_u64_le(self.time_usec);
20583 __tmp.put_f32_le(self.x);
20584 __tmp.put_f32_le(self.y);
20585 __tmp.put_f32_le(self.z);
20586 for val in &self.q {
20587 __tmp.put_f32_le(*val);
20588 }
20589 __tmp.put_f32_le(self.vx);
20590 __tmp.put_f32_le(self.vy);
20591 __tmp.put_f32_le(self.vz);
20592 __tmp.put_f32_le(self.rollspeed);
20593 __tmp.put_f32_le(self.pitchspeed);
20594 __tmp.put_f32_le(self.yawspeed);
20595 for val in &self.pose_covariance {
20596 __tmp.put_f32_le(*val);
20597 }
20598 for val in &self.velocity_covariance {
20599 __tmp.put_f32_le(*val);
20600 }
20601 __tmp.put_u8(self.frame_id as u8);
20602 __tmp.put_u8(self.child_frame_id as u8);
20603 __tmp.put_u8(self.reset_counter);
20604 __tmp.put_u8(self.estimator_type as u8);
20605 __tmp.put_i8(self.quality);
20606 if matches!(version, MavlinkVersion::V2) {
20607 let len = __tmp.len();
20608 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20609 } else {
20610 __tmp.len()
20611 }
20612 }
20613}
20614#[doc = "id: 390"]
20615#[doc = "Hardware status sent by an onboard computer."]
20616#[derive(Debug, Clone, PartialEq)]
20617#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20618#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20619pub struct ONBOARD_COMPUTER_STATUS_DATA {
20620 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
20621 pub time_usec: u64,
20622 #[doc = "Time since system boot."]
20623 pub uptime: u32,
20624 #[doc = "Amount of used RAM on the component system. A value of UINT32_MAX implies the field is unused."]
20625 pub ram_usage: u32,
20626 #[doc = "Total amount of RAM on the component system. A value of UINT32_MAX implies the field is unused."]
20627 pub ram_total: u32,
20628 #[doc = "Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable). A value of UINT32_MAX implies the field is unused."]
20629 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20630 pub storage_type: [u32; 4],
20631 #[doc = "Amount of used storage space on the component system. A value of UINT32_MAX implies the field is unused."]
20632 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20633 pub storage_usage: [u32; 4],
20634 #[doc = "Total amount of storage space on the component system. A value of UINT32_MAX implies the field is unused."]
20635 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20636 pub storage_total: [u32; 4],
20637 #[doc = "Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary"]
20638 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20639 pub link_type: [u32; 6],
20640 #[doc = "Network traffic from the component system. A value of UINT32_MAX implies the field is unused."]
20641 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20642 pub link_tx_rate: [u32; 6],
20643 #[doc = "Network traffic to the component system. A value of UINT32_MAX implies the field is unused."]
20644 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20645 pub link_rx_rate: [u32; 6],
20646 #[doc = "Network capacity from the component system. A value of UINT32_MAX implies the field is unused."]
20647 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20648 pub link_tx_max: [u32; 6],
20649 #[doc = "Network capacity to the component system. A value of UINT32_MAX implies the field is unused."]
20650 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20651 pub link_rx_max: [u32; 6],
20652 #[doc = "Fan speeds. A value of INT16_MAX implies the field is unused."]
20653 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20654 pub fan_speed: [i16; 4],
20655 #[doc = "Type of the onboard computer: 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers."]
20656 pub mavtype: u8,
20657 #[doc = "CPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused."]
20658 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20659 pub cpu_cores: [u8; 8],
20660 #[doc = "Combined CPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused."]
20661 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20662 pub cpu_combined: [u8; 10],
20663 #[doc = "GPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused."]
20664 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20665 pub gpu_cores: [u8; 4],
20666 #[doc = "Combined GPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused."]
20667 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20668 pub gpu_combined: [u8; 10],
20669 #[doc = "Temperature of the board. A value of INT8_MAX implies the field is unused."]
20670 pub temperature_board: i8,
20671 #[doc = "Temperature of the CPU core. A value of INT8_MAX implies the field is unused."]
20672 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20673 pub temperature_core: [i8; 8],
20674}
20675impl ONBOARD_COMPUTER_STATUS_DATA {
20676 pub const ENCODED_LEN: usize = 238usize;
20677 pub const DEFAULT: Self = Self {
20678 time_usec: 0_u64,
20679 uptime: 0_u32,
20680 ram_usage: 0_u32,
20681 ram_total: 0_u32,
20682 storage_type: [0_u32; 4usize],
20683 storage_usage: [0_u32; 4usize],
20684 storage_total: [0_u32; 4usize],
20685 link_type: [0_u32; 6usize],
20686 link_tx_rate: [0_u32; 6usize],
20687 link_rx_rate: [0_u32; 6usize],
20688 link_tx_max: [0_u32; 6usize],
20689 link_rx_max: [0_u32; 6usize],
20690 fan_speed: [0_i16; 4usize],
20691 mavtype: 0_u8,
20692 cpu_cores: [0_u8; 8usize],
20693 cpu_combined: [0_u8; 10usize],
20694 gpu_cores: [0_u8; 4usize],
20695 gpu_combined: [0_u8; 10usize],
20696 temperature_board: 0_i8,
20697 temperature_core: [0_i8; 8usize],
20698 };
20699 #[cfg(feature = "arbitrary")]
20700 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20701 use arbitrary::{Arbitrary, Unstructured};
20702 let mut buf = [0u8; 1024];
20703 rng.fill_bytes(&mut buf);
20704 let mut unstructured = Unstructured::new(&buf);
20705 Self::arbitrary(&mut unstructured).unwrap_or_default()
20706 }
20707}
20708impl Default for ONBOARD_COMPUTER_STATUS_DATA {
20709 fn default() -> Self {
20710 Self::DEFAULT.clone()
20711 }
20712}
20713impl MessageData for ONBOARD_COMPUTER_STATUS_DATA {
20714 type Message = MavMessage;
20715 const ID: u32 = 390u32;
20716 const NAME: &'static str = "ONBOARD_COMPUTER_STATUS";
20717 const EXTRA_CRC: u8 = 156u8;
20718 const ENCODED_LEN: usize = 238usize;
20719 fn deser(
20720 _version: MavlinkVersion,
20721 __input: &[u8],
20722 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20723 let avail_len = __input.len();
20724 let mut payload_buf = [0; Self::ENCODED_LEN];
20725 let mut buf = if avail_len < Self::ENCODED_LEN {
20726 payload_buf[0..avail_len].copy_from_slice(__input);
20727 Bytes::new(&payload_buf)
20728 } else {
20729 Bytes::new(__input)
20730 };
20731 let mut __struct = Self::default();
20732 __struct.time_usec = buf.get_u64_le();
20733 __struct.uptime = buf.get_u32_le();
20734 __struct.ram_usage = buf.get_u32_le();
20735 __struct.ram_total = buf.get_u32_le();
20736 for v in &mut __struct.storage_type {
20737 let val = buf.get_u32_le();
20738 *v = val;
20739 }
20740 for v in &mut __struct.storage_usage {
20741 let val = buf.get_u32_le();
20742 *v = val;
20743 }
20744 for v in &mut __struct.storage_total {
20745 let val = buf.get_u32_le();
20746 *v = val;
20747 }
20748 for v in &mut __struct.link_type {
20749 let val = buf.get_u32_le();
20750 *v = val;
20751 }
20752 for v in &mut __struct.link_tx_rate {
20753 let val = buf.get_u32_le();
20754 *v = val;
20755 }
20756 for v in &mut __struct.link_rx_rate {
20757 let val = buf.get_u32_le();
20758 *v = val;
20759 }
20760 for v in &mut __struct.link_tx_max {
20761 let val = buf.get_u32_le();
20762 *v = val;
20763 }
20764 for v in &mut __struct.link_rx_max {
20765 let val = buf.get_u32_le();
20766 *v = val;
20767 }
20768 for v in &mut __struct.fan_speed {
20769 let val = buf.get_i16_le();
20770 *v = val;
20771 }
20772 __struct.mavtype = buf.get_u8();
20773 for v in &mut __struct.cpu_cores {
20774 let val = buf.get_u8();
20775 *v = val;
20776 }
20777 for v in &mut __struct.cpu_combined {
20778 let val = buf.get_u8();
20779 *v = val;
20780 }
20781 for v in &mut __struct.gpu_cores {
20782 let val = buf.get_u8();
20783 *v = val;
20784 }
20785 for v in &mut __struct.gpu_combined {
20786 let val = buf.get_u8();
20787 *v = val;
20788 }
20789 __struct.temperature_board = buf.get_i8();
20790 for v in &mut __struct.temperature_core {
20791 let val = buf.get_i8();
20792 *v = val;
20793 }
20794 Ok(__struct)
20795 }
20796 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20797 let mut __tmp = BytesMut::new(bytes);
20798 #[allow(clippy::absurd_extreme_comparisons)]
20799 #[allow(unused_comparisons)]
20800 if __tmp.remaining() < Self::ENCODED_LEN {
20801 panic!(
20802 "buffer is too small (need {} bytes, but got {})",
20803 Self::ENCODED_LEN,
20804 __tmp.remaining(),
20805 )
20806 }
20807 __tmp.put_u64_le(self.time_usec);
20808 __tmp.put_u32_le(self.uptime);
20809 __tmp.put_u32_le(self.ram_usage);
20810 __tmp.put_u32_le(self.ram_total);
20811 for val in &self.storage_type {
20812 __tmp.put_u32_le(*val);
20813 }
20814 for val in &self.storage_usage {
20815 __tmp.put_u32_le(*val);
20816 }
20817 for val in &self.storage_total {
20818 __tmp.put_u32_le(*val);
20819 }
20820 for val in &self.link_type {
20821 __tmp.put_u32_le(*val);
20822 }
20823 for val in &self.link_tx_rate {
20824 __tmp.put_u32_le(*val);
20825 }
20826 for val in &self.link_rx_rate {
20827 __tmp.put_u32_le(*val);
20828 }
20829 for val in &self.link_tx_max {
20830 __tmp.put_u32_le(*val);
20831 }
20832 for val in &self.link_rx_max {
20833 __tmp.put_u32_le(*val);
20834 }
20835 for val in &self.fan_speed {
20836 __tmp.put_i16_le(*val);
20837 }
20838 __tmp.put_u8(self.mavtype);
20839 for val in &self.cpu_cores {
20840 __tmp.put_u8(*val);
20841 }
20842 for val in &self.cpu_combined {
20843 __tmp.put_u8(*val);
20844 }
20845 for val in &self.gpu_cores {
20846 __tmp.put_u8(*val);
20847 }
20848 for val in &self.gpu_combined {
20849 __tmp.put_u8(*val);
20850 }
20851 __tmp.put_i8(self.temperature_board);
20852 for val in &self.temperature_core {
20853 __tmp.put_i8(*val);
20854 }
20855 if matches!(version, MavlinkVersion::V2) {
20856 let len = __tmp.len();
20857 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20858 } else {
20859 __tmp.len()
20860 }
20861 }
20862}
20863#[doc = "id: 12918"]
20864#[doc = "Transmitter (remote ID system) is enabled and ready to start sending location and other required information. This is streamed by transmitter. A flight controller uses it as a condition to arm."]
20865#[derive(Debug, Clone, PartialEq)]
20866#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20867#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20868pub struct OPEN_DRONE_ID_ARM_STATUS_DATA {
20869 #[doc = "Status level indicating if arming is allowed."]
20870 pub status: MavOdidArmStatus,
20871 #[doc = "Text error message, should be empty if status is good to arm. Fill with nulls in unused portion."]
20872 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20873 pub error: [u8; 50],
20874}
20875impl OPEN_DRONE_ID_ARM_STATUS_DATA {
20876 pub const ENCODED_LEN: usize = 51usize;
20877 pub const DEFAULT: Self = Self {
20878 status: MavOdidArmStatus::DEFAULT,
20879 error: [0_u8; 50usize],
20880 };
20881 #[cfg(feature = "arbitrary")]
20882 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20883 use arbitrary::{Arbitrary, Unstructured};
20884 let mut buf = [0u8; 1024];
20885 rng.fill_bytes(&mut buf);
20886 let mut unstructured = Unstructured::new(&buf);
20887 Self::arbitrary(&mut unstructured).unwrap_or_default()
20888 }
20889}
20890impl Default for OPEN_DRONE_ID_ARM_STATUS_DATA {
20891 fn default() -> Self {
20892 Self::DEFAULT.clone()
20893 }
20894}
20895impl MessageData for OPEN_DRONE_ID_ARM_STATUS_DATA {
20896 type Message = MavMessage;
20897 const ID: u32 = 12918u32;
20898 const NAME: &'static str = "OPEN_DRONE_ID_ARM_STATUS";
20899 const EXTRA_CRC: u8 = 139u8;
20900 const ENCODED_LEN: usize = 51usize;
20901 fn deser(
20902 _version: MavlinkVersion,
20903 __input: &[u8],
20904 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20905 let avail_len = __input.len();
20906 let mut payload_buf = [0; Self::ENCODED_LEN];
20907 let mut buf = if avail_len < Self::ENCODED_LEN {
20908 payload_buf[0..avail_len].copy_from_slice(__input);
20909 Bytes::new(&payload_buf)
20910 } else {
20911 Bytes::new(__input)
20912 };
20913 let mut __struct = Self::default();
20914 let tmp = buf.get_u8();
20915 __struct.status =
20916 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
20917 enum_type: "MavOdidArmStatus",
20918 value: tmp as u32,
20919 })?;
20920 for v in &mut __struct.error {
20921 let val = buf.get_u8();
20922 *v = val;
20923 }
20924 Ok(__struct)
20925 }
20926 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20927 let mut __tmp = BytesMut::new(bytes);
20928 #[allow(clippy::absurd_extreme_comparisons)]
20929 #[allow(unused_comparisons)]
20930 if __tmp.remaining() < Self::ENCODED_LEN {
20931 panic!(
20932 "buffer is too small (need {} bytes, but got {})",
20933 Self::ENCODED_LEN,
20934 __tmp.remaining(),
20935 )
20936 }
20937 __tmp.put_u8(self.status as u8);
20938 for val in &self.error {
20939 __tmp.put_u8(*val);
20940 }
20941 if matches!(version, MavlinkVersion::V2) {
20942 let len = __tmp.len();
20943 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20944 } else {
20945 __tmp.len()
20946 }
20947 }
20948}
20949#[doc = "id: 12902"]
20950#[doc = "Data for filling the OpenDroneID Authentication message. The Authentication Message defines a field that can provide a means of authenticity for the identity of the UAS (Unmanned Aircraft System). The Authentication message can have two different formats. For data page 0, the fields PageCount, Length and TimeStamp are present and AuthData is only 17 bytes. For data page 1 through 15, PageCount, Length and TimeStamp are not present and the size of AuthData is 23 bytes."]
20951#[derive(Debug, Clone, PartialEq)]
20952#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20953#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20954pub struct OPEN_DRONE_ID_AUTHENTICATION_DATA {
20955 #[doc = "This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019."]
20956 pub timestamp: u32,
20957 #[doc = "System ID (0 for broadcast)."]
20958 pub target_system: u8,
20959 #[doc = "Component ID (0 for broadcast)."]
20960 pub target_component: u8,
20961 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
20962 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20963 pub id_or_mac: [u8; 20],
20964 #[doc = "Indicates the type of authentication."]
20965 pub authentication_type: MavOdidAuthType,
20966 #[doc = "Allowed range is 0 - 15."]
20967 pub data_page: u8,
20968 #[doc = "This field is only present for page 0. Allowed range is 0 - 15. See the description of struct ODID_Auth_data at <https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h>."]
20969 pub last_page_index: u8,
20970 #[doc = "This field is only present for page 0. Total bytes of authentication_data from all data pages. See the description of struct ODID_Auth_data at <https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h>."]
20971 pub length: u8,
20972 #[doc = "Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field."]
20973 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20974 pub authentication_data: [u8; 23],
20975}
20976impl OPEN_DRONE_ID_AUTHENTICATION_DATA {
20977 pub const ENCODED_LEN: usize = 53usize;
20978 pub const DEFAULT: Self = Self {
20979 timestamp: 0_u32,
20980 target_system: 0_u8,
20981 target_component: 0_u8,
20982 id_or_mac: [0_u8; 20usize],
20983 authentication_type: MavOdidAuthType::DEFAULT,
20984 data_page: 0_u8,
20985 last_page_index: 0_u8,
20986 length: 0_u8,
20987 authentication_data: [0_u8; 23usize],
20988 };
20989 #[cfg(feature = "arbitrary")]
20990 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20991 use arbitrary::{Arbitrary, Unstructured};
20992 let mut buf = [0u8; 1024];
20993 rng.fill_bytes(&mut buf);
20994 let mut unstructured = Unstructured::new(&buf);
20995 Self::arbitrary(&mut unstructured).unwrap_or_default()
20996 }
20997}
20998impl Default for OPEN_DRONE_ID_AUTHENTICATION_DATA {
20999 fn default() -> Self {
21000 Self::DEFAULT.clone()
21001 }
21002}
21003impl MessageData for OPEN_DRONE_ID_AUTHENTICATION_DATA {
21004 type Message = MavMessage;
21005 const ID: u32 = 12902u32;
21006 const NAME: &'static str = "OPEN_DRONE_ID_AUTHENTICATION";
21007 const EXTRA_CRC: u8 = 140u8;
21008 const ENCODED_LEN: usize = 53usize;
21009 fn deser(
21010 _version: MavlinkVersion,
21011 __input: &[u8],
21012 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21013 let avail_len = __input.len();
21014 let mut payload_buf = [0; Self::ENCODED_LEN];
21015 let mut buf = if avail_len < Self::ENCODED_LEN {
21016 payload_buf[0..avail_len].copy_from_slice(__input);
21017 Bytes::new(&payload_buf)
21018 } else {
21019 Bytes::new(__input)
21020 };
21021 let mut __struct = Self::default();
21022 __struct.timestamp = buf.get_u32_le();
21023 __struct.target_system = buf.get_u8();
21024 __struct.target_component = buf.get_u8();
21025 for v in &mut __struct.id_or_mac {
21026 let val = buf.get_u8();
21027 *v = val;
21028 }
21029 let tmp = buf.get_u8();
21030 __struct.authentication_type =
21031 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21032 enum_type: "MavOdidAuthType",
21033 value: tmp as u32,
21034 })?;
21035 __struct.data_page = buf.get_u8();
21036 __struct.last_page_index = buf.get_u8();
21037 __struct.length = buf.get_u8();
21038 for v in &mut __struct.authentication_data {
21039 let val = buf.get_u8();
21040 *v = val;
21041 }
21042 Ok(__struct)
21043 }
21044 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21045 let mut __tmp = BytesMut::new(bytes);
21046 #[allow(clippy::absurd_extreme_comparisons)]
21047 #[allow(unused_comparisons)]
21048 if __tmp.remaining() < Self::ENCODED_LEN {
21049 panic!(
21050 "buffer is too small (need {} bytes, but got {})",
21051 Self::ENCODED_LEN,
21052 __tmp.remaining(),
21053 )
21054 }
21055 __tmp.put_u32_le(self.timestamp);
21056 __tmp.put_u8(self.target_system);
21057 __tmp.put_u8(self.target_component);
21058 for val in &self.id_or_mac {
21059 __tmp.put_u8(*val);
21060 }
21061 __tmp.put_u8(self.authentication_type as u8);
21062 __tmp.put_u8(self.data_page);
21063 __tmp.put_u8(self.last_page_index);
21064 __tmp.put_u8(self.length);
21065 for val in &self.authentication_data {
21066 __tmp.put_u8(*val);
21067 }
21068 if matches!(version, MavlinkVersion::V2) {
21069 let len = __tmp.len();
21070 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21071 } else {
21072 __tmp.len()
21073 }
21074 }
21075}
21076#[doc = "id: 12900"]
21077#[doc = "Data for filling the OpenDroneID Basic ID message. This and the below messages are primarily meant for feeding data to/from an OpenDroneID implementation. E.g. <https://github.com/opendroneid/opendroneid-core-c>. These messages are compatible with the ASTM F3411 Remote ID standard and the ASD-STAN prEN 4709-002 Direct Remote ID standard. Additional information and usage of these messages is documented at <https://mavlink.io/en/services/opendroneid.html>."]
21078#[derive(Debug, Clone, PartialEq)]
21079#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21080#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21081pub struct OPEN_DRONE_ID_BASIC_ID_DATA {
21082 #[doc = "System ID (0 for broadcast)."]
21083 pub target_system: u8,
21084 #[doc = "Component ID (0 for broadcast)."]
21085 pub target_component: u8,
21086 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
21087 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21088 pub id_or_mac: [u8; 20],
21089 #[doc = "Indicates the format for the uas_id field of this message."]
21090 pub id_type: MavOdidIdType,
21091 #[doc = "Indicates the type of UA (Unmanned Aircraft)."]
21092 pub ua_type: MavOdidUaType,
21093 #[doc = "UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field."]
21094 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21095 pub uas_id: [u8; 20],
21096}
21097impl OPEN_DRONE_ID_BASIC_ID_DATA {
21098 pub const ENCODED_LEN: usize = 44usize;
21099 pub const DEFAULT: Self = Self {
21100 target_system: 0_u8,
21101 target_component: 0_u8,
21102 id_or_mac: [0_u8; 20usize],
21103 id_type: MavOdidIdType::DEFAULT,
21104 ua_type: MavOdidUaType::DEFAULT,
21105 uas_id: [0_u8; 20usize],
21106 };
21107 #[cfg(feature = "arbitrary")]
21108 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21109 use arbitrary::{Arbitrary, Unstructured};
21110 let mut buf = [0u8; 1024];
21111 rng.fill_bytes(&mut buf);
21112 let mut unstructured = Unstructured::new(&buf);
21113 Self::arbitrary(&mut unstructured).unwrap_or_default()
21114 }
21115}
21116impl Default for OPEN_DRONE_ID_BASIC_ID_DATA {
21117 fn default() -> Self {
21118 Self::DEFAULT.clone()
21119 }
21120}
21121impl MessageData for OPEN_DRONE_ID_BASIC_ID_DATA {
21122 type Message = MavMessage;
21123 const ID: u32 = 12900u32;
21124 const NAME: &'static str = "OPEN_DRONE_ID_BASIC_ID";
21125 const EXTRA_CRC: u8 = 114u8;
21126 const ENCODED_LEN: usize = 44usize;
21127 fn deser(
21128 _version: MavlinkVersion,
21129 __input: &[u8],
21130 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21131 let avail_len = __input.len();
21132 let mut payload_buf = [0; Self::ENCODED_LEN];
21133 let mut buf = if avail_len < Self::ENCODED_LEN {
21134 payload_buf[0..avail_len].copy_from_slice(__input);
21135 Bytes::new(&payload_buf)
21136 } else {
21137 Bytes::new(__input)
21138 };
21139 let mut __struct = Self::default();
21140 __struct.target_system = buf.get_u8();
21141 __struct.target_component = buf.get_u8();
21142 for v in &mut __struct.id_or_mac {
21143 let val = buf.get_u8();
21144 *v = val;
21145 }
21146 let tmp = buf.get_u8();
21147 __struct.id_type =
21148 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21149 enum_type: "MavOdidIdType",
21150 value: tmp as u32,
21151 })?;
21152 let tmp = buf.get_u8();
21153 __struct.ua_type =
21154 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21155 enum_type: "MavOdidUaType",
21156 value: tmp as u32,
21157 })?;
21158 for v in &mut __struct.uas_id {
21159 let val = buf.get_u8();
21160 *v = val;
21161 }
21162 Ok(__struct)
21163 }
21164 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21165 let mut __tmp = BytesMut::new(bytes);
21166 #[allow(clippy::absurd_extreme_comparisons)]
21167 #[allow(unused_comparisons)]
21168 if __tmp.remaining() < Self::ENCODED_LEN {
21169 panic!(
21170 "buffer is too small (need {} bytes, but got {})",
21171 Self::ENCODED_LEN,
21172 __tmp.remaining(),
21173 )
21174 }
21175 __tmp.put_u8(self.target_system);
21176 __tmp.put_u8(self.target_component);
21177 for val in &self.id_or_mac {
21178 __tmp.put_u8(*val);
21179 }
21180 __tmp.put_u8(self.id_type as u8);
21181 __tmp.put_u8(self.ua_type as u8);
21182 for val in &self.uas_id {
21183 __tmp.put_u8(*val);
21184 }
21185 if matches!(version, MavlinkVersion::V2) {
21186 let len = __tmp.len();
21187 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21188 } else {
21189 __tmp.len()
21190 }
21191 }
21192}
21193#[doc = "id: 12901"]
21194#[doc = "Data for filling the OpenDroneID Location message. The float data types are 32-bit IEEE 754. The Location message provides the location, altitude, direction and speed of the aircraft."]
21195#[derive(Debug, Clone, PartialEq)]
21196#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21197#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21198pub struct OPEN_DRONE_ID_LOCATION_DATA {
21199 #[doc = "Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon)."]
21200 pub latitude: i32,
21201 #[doc = "Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon)."]
21202 pub longitude: i32,
21203 #[doc = "The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m."]
21204 pub altitude_barometric: f32,
21205 #[doc = "The geodetic altitude as defined by WGS84. If unknown: -1000 m."]
21206 pub altitude_geodetic: f32,
21207 #[doc = "The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m."]
21208 pub height: f32,
21209 #[doc = "Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000. If unknown: 0xFFFF."]
21210 pub timestamp: f32,
21211 #[doc = "Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees."]
21212 pub direction: u16,
21213 #[doc = "Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s."]
21214 pub speed_horizontal: u16,
21215 #[doc = "The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s."]
21216 pub speed_vertical: i16,
21217 #[doc = "System ID (0 for broadcast)."]
21218 pub target_system: u8,
21219 #[doc = "Component ID (0 for broadcast)."]
21220 pub target_component: u8,
21221 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
21222 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21223 pub id_or_mac: [u8; 20],
21224 #[doc = "Indicates whether the unmanned aircraft is on the ground or in the air."]
21225 pub status: MavOdidStatus,
21226 #[doc = "Indicates the reference point for the height field."]
21227 pub height_reference: MavOdidHeightRef,
21228 #[doc = "The accuracy of the horizontal position."]
21229 pub horizontal_accuracy: MavOdidHorAcc,
21230 #[doc = "The accuracy of the vertical position."]
21231 pub vertical_accuracy: MavOdidVerAcc,
21232 #[doc = "The accuracy of the barometric altitude."]
21233 pub barometer_accuracy: MavOdidVerAcc,
21234 #[doc = "The accuracy of the horizontal and vertical speed."]
21235 pub speed_accuracy: MavOdidSpeedAcc,
21236 #[doc = "The accuracy of the timestamps."]
21237 pub timestamp_accuracy: MavOdidTimeAcc,
21238}
21239impl OPEN_DRONE_ID_LOCATION_DATA {
21240 pub const ENCODED_LEN: usize = 59usize;
21241 pub const DEFAULT: Self = Self {
21242 latitude: 0_i32,
21243 longitude: 0_i32,
21244 altitude_barometric: 0.0_f32,
21245 altitude_geodetic: 0.0_f32,
21246 height: 0.0_f32,
21247 timestamp: 0.0_f32,
21248 direction: 0_u16,
21249 speed_horizontal: 0_u16,
21250 speed_vertical: 0_i16,
21251 target_system: 0_u8,
21252 target_component: 0_u8,
21253 id_or_mac: [0_u8; 20usize],
21254 status: MavOdidStatus::DEFAULT,
21255 height_reference: MavOdidHeightRef::DEFAULT,
21256 horizontal_accuracy: MavOdidHorAcc::DEFAULT,
21257 vertical_accuracy: MavOdidVerAcc::DEFAULT,
21258 barometer_accuracy: MavOdidVerAcc::DEFAULT,
21259 speed_accuracy: MavOdidSpeedAcc::DEFAULT,
21260 timestamp_accuracy: MavOdidTimeAcc::DEFAULT,
21261 };
21262 #[cfg(feature = "arbitrary")]
21263 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21264 use arbitrary::{Arbitrary, Unstructured};
21265 let mut buf = [0u8; 1024];
21266 rng.fill_bytes(&mut buf);
21267 let mut unstructured = Unstructured::new(&buf);
21268 Self::arbitrary(&mut unstructured).unwrap_or_default()
21269 }
21270}
21271impl Default for OPEN_DRONE_ID_LOCATION_DATA {
21272 fn default() -> Self {
21273 Self::DEFAULT.clone()
21274 }
21275}
21276impl MessageData for OPEN_DRONE_ID_LOCATION_DATA {
21277 type Message = MavMessage;
21278 const ID: u32 = 12901u32;
21279 const NAME: &'static str = "OPEN_DRONE_ID_LOCATION";
21280 const EXTRA_CRC: u8 = 254u8;
21281 const ENCODED_LEN: usize = 59usize;
21282 fn deser(
21283 _version: MavlinkVersion,
21284 __input: &[u8],
21285 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21286 let avail_len = __input.len();
21287 let mut payload_buf = [0; Self::ENCODED_LEN];
21288 let mut buf = if avail_len < Self::ENCODED_LEN {
21289 payload_buf[0..avail_len].copy_from_slice(__input);
21290 Bytes::new(&payload_buf)
21291 } else {
21292 Bytes::new(__input)
21293 };
21294 let mut __struct = Self::default();
21295 __struct.latitude = buf.get_i32_le();
21296 __struct.longitude = buf.get_i32_le();
21297 __struct.altitude_barometric = buf.get_f32_le();
21298 __struct.altitude_geodetic = buf.get_f32_le();
21299 __struct.height = buf.get_f32_le();
21300 __struct.timestamp = buf.get_f32_le();
21301 __struct.direction = buf.get_u16_le();
21302 __struct.speed_horizontal = buf.get_u16_le();
21303 __struct.speed_vertical = buf.get_i16_le();
21304 __struct.target_system = buf.get_u8();
21305 __struct.target_component = buf.get_u8();
21306 for v in &mut __struct.id_or_mac {
21307 let val = buf.get_u8();
21308 *v = val;
21309 }
21310 let tmp = buf.get_u8();
21311 __struct.status =
21312 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21313 enum_type: "MavOdidStatus",
21314 value: tmp as u32,
21315 })?;
21316 let tmp = buf.get_u8();
21317 __struct.height_reference =
21318 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21319 enum_type: "MavOdidHeightRef",
21320 value: tmp as u32,
21321 })?;
21322 let tmp = buf.get_u8();
21323 __struct.horizontal_accuracy =
21324 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21325 enum_type: "MavOdidHorAcc",
21326 value: tmp as u32,
21327 })?;
21328 let tmp = buf.get_u8();
21329 __struct.vertical_accuracy =
21330 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21331 enum_type: "MavOdidVerAcc",
21332 value: tmp as u32,
21333 })?;
21334 let tmp = buf.get_u8();
21335 __struct.barometer_accuracy =
21336 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21337 enum_type: "MavOdidVerAcc",
21338 value: tmp as u32,
21339 })?;
21340 let tmp = buf.get_u8();
21341 __struct.speed_accuracy =
21342 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21343 enum_type: "MavOdidSpeedAcc",
21344 value: tmp as u32,
21345 })?;
21346 let tmp = buf.get_u8();
21347 __struct.timestamp_accuracy =
21348 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21349 enum_type: "MavOdidTimeAcc",
21350 value: tmp as u32,
21351 })?;
21352 Ok(__struct)
21353 }
21354 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21355 let mut __tmp = BytesMut::new(bytes);
21356 #[allow(clippy::absurd_extreme_comparisons)]
21357 #[allow(unused_comparisons)]
21358 if __tmp.remaining() < Self::ENCODED_LEN {
21359 panic!(
21360 "buffer is too small (need {} bytes, but got {})",
21361 Self::ENCODED_LEN,
21362 __tmp.remaining(),
21363 )
21364 }
21365 __tmp.put_i32_le(self.latitude);
21366 __tmp.put_i32_le(self.longitude);
21367 __tmp.put_f32_le(self.altitude_barometric);
21368 __tmp.put_f32_le(self.altitude_geodetic);
21369 __tmp.put_f32_le(self.height);
21370 __tmp.put_f32_le(self.timestamp);
21371 __tmp.put_u16_le(self.direction);
21372 __tmp.put_u16_le(self.speed_horizontal);
21373 __tmp.put_i16_le(self.speed_vertical);
21374 __tmp.put_u8(self.target_system);
21375 __tmp.put_u8(self.target_component);
21376 for val in &self.id_or_mac {
21377 __tmp.put_u8(*val);
21378 }
21379 __tmp.put_u8(self.status as u8);
21380 __tmp.put_u8(self.height_reference as u8);
21381 __tmp.put_u8(self.horizontal_accuracy as u8);
21382 __tmp.put_u8(self.vertical_accuracy as u8);
21383 __tmp.put_u8(self.barometer_accuracy as u8);
21384 __tmp.put_u8(self.speed_accuracy as u8);
21385 __tmp.put_u8(self.timestamp_accuracy as u8);
21386 if matches!(version, MavlinkVersion::V2) {
21387 let len = __tmp.len();
21388 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21389 } else {
21390 __tmp.len()
21391 }
21392 }
21393}
21394#[doc = "id: 12915"]
21395#[doc = "An OpenDroneID message pack is a container for multiple encoded OpenDroneID messages (i.e. not in the format given for the above message descriptions but after encoding into the compressed OpenDroneID byte format). Used e.g. when transmitting on Bluetooth 5.0 Long Range/Extended Advertising or on WiFi Neighbor Aware Networking or on WiFi Beacon."]
21396#[derive(Debug, Clone, PartialEq)]
21397#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21398#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21399pub struct OPEN_DRONE_ID_MESSAGE_PACK_DATA {
21400 #[doc = "System ID (0 for broadcast)."]
21401 pub target_system: u8,
21402 #[doc = "Component ID (0 for broadcast)."]
21403 pub target_component: u8,
21404 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
21405 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21406 pub id_or_mac: [u8; 20],
21407 #[doc = "This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specified to have this length."]
21408 pub single_message_size: u8,
21409 #[doc = "Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 9."]
21410 pub msg_pack_size: u8,
21411 #[doc = "Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field."]
21412 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21413 pub messages: [u8; 225],
21414}
21415impl OPEN_DRONE_ID_MESSAGE_PACK_DATA {
21416 pub const ENCODED_LEN: usize = 249usize;
21417 pub const DEFAULT: Self = Self {
21418 target_system: 0_u8,
21419 target_component: 0_u8,
21420 id_or_mac: [0_u8; 20usize],
21421 single_message_size: 0_u8,
21422 msg_pack_size: 0_u8,
21423 messages: [0_u8; 225usize],
21424 };
21425 #[cfg(feature = "arbitrary")]
21426 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21427 use arbitrary::{Arbitrary, Unstructured};
21428 let mut buf = [0u8; 1024];
21429 rng.fill_bytes(&mut buf);
21430 let mut unstructured = Unstructured::new(&buf);
21431 Self::arbitrary(&mut unstructured).unwrap_or_default()
21432 }
21433}
21434impl Default for OPEN_DRONE_ID_MESSAGE_PACK_DATA {
21435 fn default() -> Self {
21436 Self::DEFAULT.clone()
21437 }
21438}
21439impl MessageData for OPEN_DRONE_ID_MESSAGE_PACK_DATA {
21440 type Message = MavMessage;
21441 const ID: u32 = 12915u32;
21442 const NAME: &'static str = "OPEN_DRONE_ID_MESSAGE_PACK";
21443 const EXTRA_CRC: u8 = 94u8;
21444 const ENCODED_LEN: usize = 249usize;
21445 fn deser(
21446 _version: MavlinkVersion,
21447 __input: &[u8],
21448 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21449 let avail_len = __input.len();
21450 let mut payload_buf = [0; Self::ENCODED_LEN];
21451 let mut buf = if avail_len < Self::ENCODED_LEN {
21452 payload_buf[0..avail_len].copy_from_slice(__input);
21453 Bytes::new(&payload_buf)
21454 } else {
21455 Bytes::new(__input)
21456 };
21457 let mut __struct = Self::default();
21458 __struct.target_system = buf.get_u8();
21459 __struct.target_component = buf.get_u8();
21460 for v in &mut __struct.id_or_mac {
21461 let val = buf.get_u8();
21462 *v = val;
21463 }
21464 __struct.single_message_size = buf.get_u8();
21465 __struct.msg_pack_size = buf.get_u8();
21466 for v in &mut __struct.messages {
21467 let val = buf.get_u8();
21468 *v = val;
21469 }
21470 Ok(__struct)
21471 }
21472 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21473 let mut __tmp = BytesMut::new(bytes);
21474 #[allow(clippy::absurd_extreme_comparisons)]
21475 #[allow(unused_comparisons)]
21476 if __tmp.remaining() < Self::ENCODED_LEN {
21477 panic!(
21478 "buffer is too small (need {} bytes, but got {})",
21479 Self::ENCODED_LEN,
21480 __tmp.remaining(),
21481 )
21482 }
21483 __tmp.put_u8(self.target_system);
21484 __tmp.put_u8(self.target_component);
21485 for val in &self.id_or_mac {
21486 __tmp.put_u8(*val);
21487 }
21488 __tmp.put_u8(self.single_message_size);
21489 __tmp.put_u8(self.msg_pack_size);
21490 for val in &self.messages {
21491 __tmp.put_u8(*val);
21492 }
21493 if matches!(version, MavlinkVersion::V2) {
21494 let len = __tmp.len();
21495 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21496 } else {
21497 __tmp.len()
21498 }
21499 }
21500}
21501#[doc = "id: 12905"]
21502#[doc = "Data for filling the OpenDroneID Operator ID message, which contains the CAA (Civil Aviation Authority) issued operator ID."]
21503#[derive(Debug, Clone, PartialEq)]
21504#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21505#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21506pub struct OPEN_DRONE_ID_OPERATOR_ID_DATA {
21507 #[doc = "System ID (0 for broadcast)."]
21508 pub target_system: u8,
21509 #[doc = "Component ID (0 for broadcast)."]
21510 pub target_component: u8,
21511 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
21512 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21513 pub id_or_mac: [u8; 20],
21514 #[doc = "Indicates the type of the operator_id field."]
21515 pub operator_id_type: MavOdidOperatorIdType,
21516 #[doc = "Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field."]
21517 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21518 pub operator_id: [u8; 20],
21519}
21520impl OPEN_DRONE_ID_OPERATOR_ID_DATA {
21521 pub const ENCODED_LEN: usize = 43usize;
21522 pub const DEFAULT: Self = Self {
21523 target_system: 0_u8,
21524 target_component: 0_u8,
21525 id_or_mac: [0_u8; 20usize],
21526 operator_id_type: MavOdidOperatorIdType::DEFAULT,
21527 operator_id: [0_u8; 20usize],
21528 };
21529 #[cfg(feature = "arbitrary")]
21530 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21531 use arbitrary::{Arbitrary, Unstructured};
21532 let mut buf = [0u8; 1024];
21533 rng.fill_bytes(&mut buf);
21534 let mut unstructured = Unstructured::new(&buf);
21535 Self::arbitrary(&mut unstructured).unwrap_or_default()
21536 }
21537}
21538impl Default for OPEN_DRONE_ID_OPERATOR_ID_DATA {
21539 fn default() -> Self {
21540 Self::DEFAULT.clone()
21541 }
21542}
21543impl MessageData for OPEN_DRONE_ID_OPERATOR_ID_DATA {
21544 type Message = MavMessage;
21545 const ID: u32 = 12905u32;
21546 const NAME: &'static str = "OPEN_DRONE_ID_OPERATOR_ID";
21547 const EXTRA_CRC: u8 = 49u8;
21548 const ENCODED_LEN: usize = 43usize;
21549 fn deser(
21550 _version: MavlinkVersion,
21551 __input: &[u8],
21552 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21553 let avail_len = __input.len();
21554 let mut payload_buf = [0; Self::ENCODED_LEN];
21555 let mut buf = if avail_len < Self::ENCODED_LEN {
21556 payload_buf[0..avail_len].copy_from_slice(__input);
21557 Bytes::new(&payload_buf)
21558 } else {
21559 Bytes::new(__input)
21560 };
21561 let mut __struct = Self::default();
21562 __struct.target_system = buf.get_u8();
21563 __struct.target_component = buf.get_u8();
21564 for v in &mut __struct.id_or_mac {
21565 let val = buf.get_u8();
21566 *v = val;
21567 }
21568 let tmp = buf.get_u8();
21569 __struct.operator_id_type =
21570 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21571 enum_type: "MavOdidOperatorIdType",
21572 value: tmp as u32,
21573 })?;
21574 for v in &mut __struct.operator_id {
21575 let val = buf.get_u8();
21576 *v = val;
21577 }
21578 Ok(__struct)
21579 }
21580 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21581 let mut __tmp = BytesMut::new(bytes);
21582 #[allow(clippy::absurd_extreme_comparisons)]
21583 #[allow(unused_comparisons)]
21584 if __tmp.remaining() < Self::ENCODED_LEN {
21585 panic!(
21586 "buffer is too small (need {} bytes, but got {})",
21587 Self::ENCODED_LEN,
21588 __tmp.remaining(),
21589 )
21590 }
21591 __tmp.put_u8(self.target_system);
21592 __tmp.put_u8(self.target_component);
21593 for val in &self.id_or_mac {
21594 __tmp.put_u8(*val);
21595 }
21596 __tmp.put_u8(self.operator_id_type as u8);
21597 for val in &self.operator_id {
21598 __tmp.put_u8(*val);
21599 }
21600 if matches!(version, MavlinkVersion::V2) {
21601 let len = __tmp.len();
21602 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21603 } else {
21604 __tmp.len()
21605 }
21606 }
21607}
21608#[doc = "id: 12903"]
21609#[doc = "Data for filling the OpenDroneID Self ID message. The Self ID Message is an opportunity for the operator to (optionally) declare their identity and purpose of the flight. This message can provide additional information that could reduce the threat profile of a UA (Unmanned Aircraft) flying in a particular area or manner. This message can also be used to provide optional additional clarification in an emergency/remote ID system failure situation."]
21610#[derive(Debug, Clone, PartialEq)]
21611#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21612#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21613pub struct OPEN_DRONE_ID_SELF_ID_DATA {
21614 #[doc = "System ID (0 for broadcast)."]
21615 pub target_system: u8,
21616 #[doc = "Component ID (0 for broadcast)."]
21617 pub target_component: u8,
21618 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
21619 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21620 pub id_or_mac: [u8; 20],
21621 #[doc = "Indicates the type of the description field."]
21622 pub description_type: MavOdidDescType,
21623 #[doc = "Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field."]
21624 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21625 pub description: [u8; 23],
21626}
21627impl OPEN_DRONE_ID_SELF_ID_DATA {
21628 pub const ENCODED_LEN: usize = 46usize;
21629 pub const DEFAULT: Self = Self {
21630 target_system: 0_u8,
21631 target_component: 0_u8,
21632 id_or_mac: [0_u8; 20usize],
21633 description_type: MavOdidDescType::DEFAULT,
21634 description: [0_u8; 23usize],
21635 };
21636 #[cfg(feature = "arbitrary")]
21637 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21638 use arbitrary::{Arbitrary, Unstructured};
21639 let mut buf = [0u8; 1024];
21640 rng.fill_bytes(&mut buf);
21641 let mut unstructured = Unstructured::new(&buf);
21642 Self::arbitrary(&mut unstructured).unwrap_or_default()
21643 }
21644}
21645impl Default for OPEN_DRONE_ID_SELF_ID_DATA {
21646 fn default() -> Self {
21647 Self::DEFAULT.clone()
21648 }
21649}
21650impl MessageData for OPEN_DRONE_ID_SELF_ID_DATA {
21651 type Message = MavMessage;
21652 const ID: u32 = 12903u32;
21653 const NAME: &'static str = "OPEN_DRONE_ID_SELF_ID";
21654 const EXTRA_CRC: u8 = 249u8;
21655 const ENCODED_LEN: usize = 46usize;
21656 fn deser(
21657 _version: MavlinkVersion,
21658 __input: &[u8],
21659 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21660 let avail_len = __input.len();
21661 let mut payload_buf = [0; Self::ENCODED_LEN];
21662 let mut buf = if avail_len < Self::ENCODED_LEN {
21663 payload_buf[0..avail_len].copy_from_slice(__input);
21664 Bytes::new(&payload_buf)
21665 } else {
21666 Bytes::new(__input)
21667 };
21668 let mut __struct = Self::default();
21669 __struct.target_system = buf.get_u8();
21670 __struct.target_component = buf.get_u8();
21671 for v in &mut __struct.id_or_mac {
21672 let val = buf.get_u8();
21673 *v = val;
21674 }
21675 let tmp = buf.get_u8();
21676 __struct.description_type =
21677 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21678 enum_type: "MavOdidDescType",
21679 value: tmp as u32,
21680 })?;
21681 for v in &mut __struct.description {
21682 let val = buf.get_u8();
21683 *v = val;
21684 }
21685 Ok(__struct)
21686 }
21687 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21688 let mut __tmp = BytesMut::new(bytes);
21689 #[allow(clippy::absurd_extreme_comparisons)]
21690 #[allow(unused_comparisons)]
21691 if __tmp.remaining() < Self::ENCODED_LEN {
21692 panic!(
21693 "buffer is too small (need {} bytes, but got {})",
21694 Self::ENCODED_LEN,
21695 __tmp.remaining(),
21696 )
21697 }
21698 __tmp.put_u8(self.target_system);
21699 __tmp.put_u8(self.target_component);
21700 for val in &self.id_or_mac {
21701 __tmp.put_u8(*val);
21702 }
21703 __tmp.put_u8(self.description_type as u8);
21704 for val in &self.description {
21705 __tmp.put_u8(*val);
21706 }
21707 if matches!(version, MavlinkVersion::V2) {
21708 let len = __tmp.len();
21709 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21710 } else {
21711 __tmp.len()
21712 }
21713 }
21714}
21715#[doc = "id: 12904"]
21716#[doc = "Data for filling the OpenDroneID System message. The System Message contains general system information including the operator location/altitude and possible aircraft group and/or category/class information."]
21717#[derive(Debug, Clone, PartialEq)]
21718#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21719#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21720pub struct OPEN_DRONE_ID_SYSTEM_DATA {
21721 #[doc = "Latitude of the operator. If unknown: 0 (both Lat/Lon)."]
21722 pub operator_latitude: i32,
21723 #[doc = "Longitude of the operator. If unknown: 0 (both Lat/Lon)."]
21724 pub operator_longitude: i32,
21725 #[doc = "Area Operations Ceiling relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA."]
21726 pub area_ceiling: f32,
21727 #[doc = "Area Operations Floor relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA."]
21728 pub area_floor: f32,
21729 #[doc = "Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m."]
21730 pub operator_altitude_geo: f32,
21731 #[doc = "32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019."]
21732 pub timestamp: u32,
21733 #[doc = "Number of aircraft in the area, group or formation (default 1). Used only for swarms/multiple UA."]
21734 pub area_count: u16,
21735 #[doc = "Radius of the cylindrical area of the group or formation (default 0). Used only for swarms/multiple UA."]
21736 pub area_radius: u16,
21737 #[doc = "System ID (0 for broadcast)."]
21738 pub target_system: u8,
21739 #[doc = "Component ID (0 for broadcast)."]
21740 pub target_component: u8,
21741 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
21742 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21743 pub id_or_mac: [u8; 20],
21744 #[doc = "Specifies the operator location type."]
21745 pub operator_location_type: MavOdidOperatorLocationType,
21746 #[doc = "Specifies the classification type of the UA."]
21747 pub classification_type: MavOdidClassificationType,
21748 #[doc = "When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA."]
21749 pub category_eu: MavOdidCategoryEu,
21750 #[doc = "When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA."]
21751 pub class_eu: MavOdidClassEu,
21752}
21753impl OPEN_DRONE_ID_SYSTEM_DATA {
21754 pub const ENCODED_LEN: usize = 54usize;
21755 pub const DEFAULT: Self = Self {
21756 operator_latitude: 0_i32,
21757 operator_longitude: 0_i32,
21758 area_ceiling: 0.0_f32,
21759 area_floor: 0.0_f32,
21760 operator_altitude_geo: 0.0_f32,
21761 timestamp: 0_u32,
21762 area_count: 0_u16,
21763 area_radius: 0_u16,
21764 target_system: 0_u8,
21765 target_component: 0_u8,
21766 id_or_mac: [0_u8; 20usize],
21767 operator_location_type: MavOdidOperatorLocationType::DEFAULT,
21768 classification_type: MavOdidClassificationType::DEFAULT,
21769 category_eu: MavOdidCategoryEu::DEFAULT,
21770 class_eu: MavOdidClassEu::DEFAULT,
21771 };
21772 #[cfg(feature = "arbitrary")]
21773 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21774 use arbitrary::{Arbitrary, Unstructured};
21775 let mut buf = [0u8; 1024];
21776 rng.fill_bytes(&mut buf);
21777 let mut unstructured = Unstructured::new(&buf);
21778 Self::arbitrary(&mut unstructured).unwrap_or_default()
21779 }
21780}
21781impl Default for OPEN_DRONE_ID_SYSTEM_DATA {
21782 fn default() -> Self {
21783 Self::DEFAULT.clone()
21784 }
21785}
21786impl MessageData for OPEN_DRONE_ID_SYSTEM_DATA {
21787 type Message = MavMessage;
21788 const ID: u32 = 12904u32;
21789 const NAME: &'static str = "OPEN_DRONE_ID_SYSTEM";
21790 const EXTRA_CRC: u8 = 77u8;
21791 const ENCODED_LEN: usize = 54usize;
21792 fn deser(
21793 _version: MavlinkVersion,
21794 __input: &[u8],
21795 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21796 let avail_len = __input.len();
21797 let mut payload_buf = [0; Self::ENCODED_LEN];
21798 let mut buf = if avail_len < Self::ENCODED_LEN {
21799 payload_buf[0..avail_len].copy_from_slice(__input);
21800 Bytes::new(&payload_buf)
21801 } else {
21802 Bytes::new(__input)
21803 };
21804 let mut __struct = Self::default();
21805 __struct.operator_latitude = buf.get_i32_le();
21806 __struct.operator_longitude = buf.get_i32_le();
21807 __struct.area_ceiling = buf.get_f32_le();
21808 __struct.area_floor = buf.get_f32_le();
21809 __struct.operator_altitude_geo = buf.get_f32_le();
21810 __struct.timestamp = buf.get_u32_le();
21811 __struct.area_count = buf.get_u16_le();
21812 __struct.area_radius = buf.get_u16_le();
21813 __struct.target_system = buf.get_u8();
21814 __struct.target_component = buf.get_u8();
21815 for v in &mut __struct.id_or_mac {
21816 let val = buf.get_u8();
21817 *v = val;
21818 }
21819 let tmp = buf.get_u8();
21820 __struct.operator_location_type =
21821 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21822 enum_type: "MavOdidOperatorLocationType",
21823 value: tmp as u32,
21824 })?;
21825 let tmp = buf.get_u8();
21826 __struct.classification_type =
21827 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21828 enum_type: "MavOdidClassificationType",
21829 value: tmp as u32,
21830 })?;
21831 let tmp = buf.get_u8();
21832 __struct.category_eu =
21833 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21834 enum_type: "MavOdidCategoryEu",
21835 value: tmp as u32,
21836 })?;
21837 let tmp = buf.get_u8();
21838 __struct.class_eu =
21839 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21840 enum_type: "MavOdidClassEu",
21841 value: tmp as u32,
21842 })?;
21843 Ok(__struct)
21844 }
21845 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21846 let mut __tmp = BytesMut::new(bytes);
21847 #[allow(clippy::absurd_extreme_comparisons)]
21848 #[allow(unused_comparisons)]
21849 if __tmp.remaining() < Self::ENCODED_LEN {
21850 panic!(
21851 "buffer is too small (need {} bytes, but got {})",
21852 Self::ENCODED_LEN,
21853 __tmp.remaining(),
21854 )
21855 }
21856 __tmp.put_i32_le(self.operator_latitude);
21857 __tmp.put_i32_le(self.operator_longitude);
21858 __tmp.put_f32_le(self.area_ceiling);
21859 __tmp.put_f32_le(self.area_floor);
21860 __tmp.put_f32_le(self.operator_altitude_geo);
21861 __tmp.put_u32_le(self.timestamp);
21862 __tmp.put_u16_le(self.area_count);
21863 __tmp.put_u16_le(self.area_radius);
21864 __tmp.put_u8(self.target_system);
21865 __tmp.put_u8(self.target_component);
21866 for val in &self.id_or_mac {
21867 __tmp.put_u8(*val);
21868 }
21869 __tmp.put_u8(self.operator_location_type as u8);
21870 __tmp.put_u8(self.classification_type as u8);
21871 __tmp.put_u8(self.category_eu as u8);
21872 __tmp.put_u8(self.class_eu as u8);
21873 if matches!(version, MavlinkVersion::V2) {
21874 let len = __tmp.len();
21875 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21876 } else {
21877 __tmp.len()
21878 }
21879 }
21880}
21881#[doc = "id: 12919"]
21882#[doc = "Update the data in the OPEN_DRONE_ID_SYSTEM message with new location information. This can be sent to update the location information for the operator when no other information in the SYSTEM message has changed. This message allows for efficient operation on radio links which have limited uplink bandwidth while meeting requirements for update frequency of the operator location."]
21883#[derive(Debug, Clone, PartialEq)]
21884#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21885#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21886pub struct OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
21887 #[doc = "Latitude of the operator. If unknown: 0 (both Lat/Lon)."]
21888 pub operator_latitude: i32,
21889 #[doc = "Longitude of the operator. If unknown: 0 (both Lat/Lon)."]
21890 pub operator_longitude: i32,
21891 #[doc = "Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m."]
21892 pub operator_altitude_geo: f32,
21893 #[doc = "32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019."]
21894 pub timestamp: u32,
21895 #[doc = "System ID (0 for broadcast)."]
21896 pub target_system: u8,
21897 #[doc = "Component ID (0 for broadcast)."]
21898 pub target_component: u8,
21899}
21900impl OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
21901 pub const ENCODED_LEN: usize = 18usize;
21902 pub const DEFAULT: Self = Self {
21903 operator_latitude: 0_i32,
21904 operator_longitude: 0_i32,
21905 operator_altitude_geo: 0.0_f32,
21906 timestamp: 0_u32,
21907 target_system: 0_u8,
21908 target_component: 0_u8,
21909 };
21910 #[cfg(feature = "arbitrary")]
21911 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21912 use arbitrary::{Arbitrary, Unstructured};
21913 let mut buf = [0u8; 1024];
21914 rng.fill_bytes(&mut buf);
21915 let mut unstructured = Unstructured::new(&buf);
21916 Self::arbitrary(&mut unstructured).unwrap_or_default()
21917 }
21918}
21919impl Default for OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
21920 fn default() -> Self {
21921 Self::DEFAULT.clone()
21922 }
21923}
21924impl MessageData for OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
21925 type Message = MavMessage;
21926 const ID: u32 = 12919u32;
21927 const NAME: &'static str = "OPEN_DRONE_ID_SYSTEM_UPDATE";
21928 const EXTRA_CRC: u8 = 7u8;
21929 const ENCODED_LEN: usize = 18usize;
21930 fn deser(
21931 _version: MavlinkVersion,
21932 __input: &[u8],
21933 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21934 let avail_len = __input.len();
21935 let mut payload_buf = [0; Self::ENCODED_LEN];
21936 let mut buf = if avail_len < Self::ENCODED_LEN {
21937 payload_buf[0..avail_len].copy_from_slice(__input);
21938 Bytes::new(&payload_buf)
21939 } else {
21940 Bytes::new(__input)
21941 };
21942 let mut __struct = Self::default();
21943 __struct.operator_latitude = buf.get_i32_le();
21944 __struct.operator_longitude = buf.get_i32_le();
21945 __struct.operator_altitude_geo = buf.get_f32_le();
21946 __struct.timestamp = buf.get_u32_le();
21947 __struct.target_system = buf.get_u8();
21948 __struct.target_component = buf.get_u8();
21949 Ok(__struct)
21950 }
21951 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21952 let mut __tmp = BytesMut::new(bytes);
21953 #[allow(clippy::absurd_extreme_comparisons)]
21954 #[allow(unused_comparisons)]
21955 if __tmp.remaining() < Self::ENCODED_LEN {
21956 panic!(
21957 "buffer is too small (need {} bytes, but got {})",
21958 Self::ENCODED_LEN,
21959 __tmp.remaining(),
21960 )
21961 }
21962 __tmp.put_i32_le(self.operator_latitude);
21963 __tmp.put_i32_le(self.operator_longitude);
21964 __tmp.put_f32_le(self.operator_altitude_geo);
21965 __tmp.put_u32_le(self.timestamp);
21966 __tmp.put_u8(self.target_system);
21967 __tmp.put_u8(self.target_component);
21968 if matches!(version, MavlinkVersion::V2) {
21969 let len = __tmp.len();
21970 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21971 } else {
21972 __tmp.len()
21973 }
21974 }
21975}
21976#[doc = "id: 100"]
21977#[doc = "Optical flow from a flow sensor (e.g. optical mouse sensor)."]
21978#[derive(Debug, Clone, PartialEq)]
21979#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21980#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21981pub struct OPTICAL_FLOW_DATA {
21982 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
21983 pub time_usec: u64,
21984 #[doc = "Flow in x-sensor direction, angular-speed compensated"]
21985 pub flow_comp_m_x: f32,
21986 #[doc = "Flow in y-sensor direction, angular-speed compensated"]
21987 pub flow_comp_m_y: f32,
21988 #[doc = "Ground distance. Positive value: distance known. Negative value: Unknown distance"]
21989 pub ground_distance: f32,
21990 #[doc = "Flow in x-sensor direction"]
21991 pub flow_x: i16,
21992 #[doc = "Flow in y-sensor direction"]
21993 pub flow_y: i16,
21994 #[doc = "Sensor ID"]
21995 pub sensor_id: u8,
21996 #[doc = "Optical flow quality / confidence. 0: bad, 255: maximum quality"]
21997 pub quality: u8,
21998 #[doc = "Flow rate about X axis"]
21999 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
22000 pub flow_rate_x: f32,
22001 #[doc = "Flow rate about Y axis"]
22002 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
22003 pub flow_rate_y: f32,
22004}
22005impl OPTICAL_FLOW_DATA {
22006 pub const ENCODED_LEN: usize = 34usize;
22007 pub const DEFAULT: Self = Self {
22008 time_usec: 0_u64,
22009 flow_comp_m_x: 0.0_f32,
22010 flow_comp_m_y: 0.0_f32,
22011 ground_distance: 0.0_f32,
22012 flow_x: 0_i16,
22013 flow_y: 0_i16,
22014 sensor_id: 0_u8,
22015 quality: 0_u8,
22016 flow_rate_x: 0.0_f32,
22017 flow_rate_y: 0.0_f32,
22018 };
22019 #[cfg(feature = "arbitrary")]
22020 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22021 use arbitrary::{Arbitrary, Unstructured};
22022 let mut buf = [0u8; 1024];
22023 rng.fill_bytes(&mut buf);
22024 let mut unstructured = Unstructured::new(&buf);
22025 Self::arbitrary(&mut unstructured).unwrap_or_default()
22026 }
22027}
22028impl Default for OPTICAL_FLOW_DATA {
22029 fn default() -> Self {
22030 Self::DEFAULT.clone()
22031 }
22032}
22033impl MessageData for OPTICAL_FLOW_DATA {
22034 type Message = MavMessage;
22035 const ID: u32 = 100u32;
22036 const NAME: &'static str = "OPTICAL_FLOW";
22037 const EXTRA_CRC: u8 = 175u8;
22038 const ENCODED_LEN: usize = 34usize;
22039 fn deser(
22040 _version: MavlinkVersion,
22041 __input: &[u8],
22042 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22043 let avail_len = __input.len();
22044 let mut payload_buf = [0; Self::ENCODED_LEN];
22045 let mut buf = if avail_len < Self::ENCODED_LEN {
22046 payload_buf[0..avail_len].copy_from_slice(__input);
22047 Bytes::new(&payload_buf)
22048 } else {
22049 Bytes::new(__input)
22050 };
22051 let mut __struct = Self::default();
22052 __struct.time_usec = buf.get_u64_le();
22053 __struct.flow_comp_m_x = buf.get_f32_le();
22054 __struct.flow_comp_m_y = buf.get_f32_le();
22055 __struct.ground_distance = buf.get_f32_le();
22056 __struct.flow_x = buf.get_i16_le();
22057 __struct.flow_y = buf.get_i16_le();
22058 __struct.sensor_id = buf.get_u8();
22059 __struct.quality = buf.get_u8();
22060 __struct.flow_rate_x = buf.get_f32_le();
22061 __struct.flow_rate_y = buf.get_f32_le();
22062 Ok(__struct)
22063 }
22064 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22065 let mut __tmp = BytesMut::new(bytes);
22066 #[allow(clippy::absurd_extreme_comparisons)]
22067 #[allow(unused_comparisons)]
22068 if __tmp.remaining() < Self::ENCODED_LEN {
22069 panic!(
22070 "buffer is too small (need {} bytes, but got {})",
22071 Self::ENCODED_LEN,
22072 __tmp.remaining(),
22073 )
22074 }
22075 __tmp.put_u64_le(self.time_usec);
22076 __tmp.put_f32_le(self.flow_comp_m_x);
22077 __tmp.put_f32_le(self.flow_comp_m_y);
22078 __tmp.put_f32_le(self.ground_distance);
22079 __tmp.put_i16_le(self.flow_x);
22080 __tmp.put_i16_le(self.flow_y);
22081 __tmp.put_u8(self.sensor_id);
22082 __tmp.put_u8(self.quality);
22083 __tmp.put_f32_le(self.flow_rate_x);
22084 __tmp.put_f32_le(self.flow_rate_y);
22085 if matches!(version, MavlinkVersion::V2) {
22086 let len = __tmp.len();
22087 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22088 } else {
22089 __tmp.len()
22090 }
22091 }
22092}
22093#[doc = "id: 106"]
22094#[doc = "Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor)."]
22095#[derive(Debug, Clone, PartialEq)]
22096#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22097#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22098pub struct OPTICAL_FLOW_RAD_DATA {
22099 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
22100 pub time_usec: u64,
22101 #[doc = "Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the."]
22102 pub integration_time_us: u32,
22103 #[doc = "Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)"]
22104 pub integrated_x: f32,
22105 #[doc = "Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)"]
22106 pub integrated_y: f32,
22107 #[doc = "RH rotation around X axis"]
22108 pub integrated_xgyro: f32,
22109 #[doc = "RH rotation around Y axis"]
22110 pub integrated_ygyro: f32,
22111 #[doc = "RH rotation around Z axis"]
22112 pub integrated_zgyro: f32,
22113 #[doc = "Time since the distance was sampled."]
22114 pub time_delta_distance_us: u32,
22115 #[doc = "Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance."]
22116 pub distance: f32,
22117 #[doc = "Temperature"]
22118 pub temperature: i16,
22119 #[doc = "Sensor ID"]
22120 pub sensor_id: u8,
22121 #[doc = "Optical flow quality / confidence. 0: no valid flow, 255: maximum quality"]
22122 pub quality: u8,
22123}
22124impl OPTICAL_FLOW_RAD_DATA {
22125 pub const ENCODED_LEN: usize = 44usize;
22126 pub const DEFAULT: Self = Self {
22127 time_usec: 0_u64,
22128 integration_time_us: 0_u32,
22129 integrated_x: 0.0_f32,
22130 integrated_y: 0.0_f32,
22131 integrated_xgyro: 0.0_f32,
22132 integrated_ygyro: 0.0_f32,
22133 integrated_zgyro: 0.0_f32,
22134 time_delta_distance_us: 0_u32,
22135 distance: 0.0_f32,
22136 temperature: 0_i16,
22137 sensor_id: 0_u8,
22138 quality: 0_u8,
22139 };
22140 #[cfg(feature = "arbitrary")]
22141 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22142 use arbitrary::{Arbitrary, Unstructured};
22143 let mut buf = [0u8; 1024];
22144 rng.fill_bytes(&mut buf);
22145 let mut unstructured = Unstructured::new(&buf);
22146 Self::arbitrary(&mut unstructured).unwrap_or_default()
22147 }
22148}
22149impl Default for OPTICAL_FLOW_RAD_DATA {
22150 fn default() -> Self {
22151 Self::DEFAULT.clone()
22152 }
22153}
22154impl MessageData for OPTICAL_FLOW_RAD_DATA {
22155 type Message = MavMessage;
22156 const ID: u32 = 106u32;
22157 const NAME: &'static str = "OPTICAL_FLOW_RAD";
22158 const EXTRA_CRC: u8 = 138u8;
22159 const ENCODED_LEN: usize = 44usize;
22160 fn deser(
22161 _version: MavlinkVersion,
22162 __input: &[u8],
22163 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22164 let avail_len = __input.len();
22165 let mut payload_buf = [0; Self::ENCODED_LEN];
22166 let mut buf = if avail_len < Self::ENCODED_LEN {
22167 payload_buf[0..avail_len].copy_from_slice(__input);
22168 Bytes::new(&payload_buf)
22169 } else {
22170 Bytes::new(__input)
22171 };
22172 let mut __struct = Self::default();
22173 __struct.time_usec = buf.get_u64_le();
22174 __struct.integration_time_us = buf.get_u32_le();
22175 __struct.integrated_x = buf.get_f32_le();
22176 __struct.integrated_y = buf.get_f32_le();
22177 __struct.integrated_xgyro = buf.get_f32_le();
22178 __struct.integrated_ygyro = buf.get_f32_le();
22179 __struct.integrated_zgyro = buf.get_f32_le();
22180 __struct.time_delta_distance_us = buf.get_u32_le();
22181 __struct.distance = buf.get_f32_le();
22182 __struct.temperature = buf.get_i16_le();
22183 __struct.sensor_id = buf.get_u8();
22184 __struct.quality = buf.get_u8();
22185 Ok(__struct)
22186 }
22187 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22188 let mut __tmp = BytesMut::new(bytes);
22189 #[allow(clippy::absurd_extreme_comparisons)]
22190 #[allow(unused_comparisons)]
22191 if __tmp.remaining() < Self::ENCODED_LEN {
22192 panic!(
22193 "buffer is too small (need {} bytes, but got {})",
22194 Self::ENCODED_LEN,
22195 __tmp.remaining(),
22196 )
22197 }
22198 __tmp.put_u64_le(self.time_usec);
22199 __tmp.put_u32_le(self.integration_time_us);
22200 __tmp.put_f32_le(self.integrated_x);
22201 __tmp.put_f32_le(self.integrated_y);
22202 __tmp.put_f32_le(self.integrated_xgyro);
22203 __tmp.put_f32_le(self.integrated_ygyro);
22204 __tmp.put_f32_le(self.integrated_zgyro);
22205 __tmp.put_u32_le(self.time_delta_distance_us);
22206 __tmp.put_f32_le(self.distance);
22207 __tmp.put_i16_le(self.temperature);
22208 __tmp.put_u8(self.sensor_id);
22209 __tmp.put_u8(self.quality);
22210 if matches!(version, MavlinkVersion::V2) {
22211 let len = __tmp.len();
22212 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22213 } else {
22214 __tmp.len()
22215 }
22216 }
22217}
22218#[doc = "id: 360"]
22219#[doc = "Vehicle status report that is sent out while orbit execution is in progress (see MAV_CMD_DO_ORBIT)."]
22220#[derive(Debug, Clone, PartialEq)]
22221#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22222#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22223pub struct ORBIT_EXECUTION_STATUS_DATA {
22224 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
22225 pub time_usec: u64,
22226 #[doc = "Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise."]
22227 pub radius: f32,
22228 #[doc = "X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7."]
22229 pub x: i32,
22230 #[doc = "Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7."]
22231 pub y: i32,
22232 #[doc = "Altitude of center point. Coordinate system depends on frame field."]
22233 pub z: f32,
22234 #[doc = "The coordinate system of the fields: x, y, z."]
22235 pub frame: MavFrame,
22236}
22237impl ORBIT_EXECUTION_STATUS_DATA {
22238 pub const ENCODED_LEN: usize = 25usize;
22239 pub const DEFAULT: Self = Self {
22240 time_usec: 0_u64,
22241 radius: 0.0_f32,
22242 x: 0_i32,
22243 y: 0_i32,
22244 z: 0.0_f32,
22245 frame: MavFrame::DEFAULT,
22246 };
22247 #[cfg(feature = "arbitrary")]
22248 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22249 use arbitrary::{Arbitrary, Unstructured};
22250 let mut buf = [0u8; 1024];
22251 rng.fill_bytes(&mut buf);
22252 let mut unstructured = Unstructured::new(&buf);
22253 Self::arbitrary(&mut unstructured).unwrap_or_default()
22254 }
22255}
22256impl Default for ORBIT_EXECUTION_STATUS_DATA {
22257 fn default() -> Self {
22258 Self::DEFAULT.clone()
22259 }
22260}
22261impl MessageData for ORBIT_EXECUTION_STATUS_DATA {
22262 type Message = MavMessage;
22263 const ID: u32 = 360u32;
22264 const NAME: &'static str = "ORBIT_EXECUTION_STATUS";
22265 const EXTRA_CRC: u8 = 11u8;
22266 const ENCODED_LEN: usize = 25usize;
22267 fn deser(
22268 _version: MavlinkVersion,
22269 __input: &[u8],
22270 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22271 let avail_len = __input.len();
22272 let mut payload_buf = [0; Self::ENCODED_LEN];
22273 let mut buf = if avail_len < Self::ENCODED_LEN {
22274 payload_buf[0..avail_len].copy_from_slice(__input);
22275 Bytes::new(&payload_buf)
22276 } else {
22277 Bytes::new(__input)
22278 };
22279 let mut __struct = Self::default();
22280 __struct.time_usec = buf.get_u64_le();
22281 __struct.radius = buf.get_f32_le();
22282 __struct.x = buf.get_i32_le();
22283 __struct.y = buf.get_i32_le();
22284 __struct.z = buf.get_f32_le();
22285 let tmp = buf.get_u8();
22286 __struct.frame =
22287 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22288 enum_type: "MavFrame",
22289 value: tmp as u32,
22290 })?;
22291 Ok(__struct)
22292 }
22293 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22294 let mut __tmp = BytesMut::new(bytes);
22295 #[allow(clippy::absurd_extreme_comparisons)]
22296 #[allow(unused_comparisons)]
22297 if __tmp.remaining() < Self::ENCODED_LEN {
22298 panic!(
22299 "buffer is too small (need {} bytes, but got {})",
22300 Self::ENCODED_LEN,
22301 __tmp.remaining(),
22302 )
22303 }
22304 __tmp.put_u64_le(self.time_usec);
22305 __tmp.put_f32_le(self.radius);
22306 __tmp.put_i32_le(self.x);
22307 __tmp.put_i32_le(self.y);
22308 __tmp.put_f32_le(self.z);
22309 __tmp.put_u8(self.frame as u8);
22310 if matches!(version, MavlinkVersion::V2) {
22311 let len = __tmp.len();
22312 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22313 } else {
22314 __tmp.len()
22315 }
22316 }
22317}
22318#[doc = "id: 324"]
22319#[doc = "Response from a PARAM_EXT_SET message."]
22320#[derive(Debug, Clone, PartialEq)]
22321#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22322#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22323pub struct PARAM_EXT_ACK_DATA {
22324 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
22325 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
22326 pub param_id: [u8; 16],
22327 #[doc = "Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise)"]
22328 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
22329 pub param_value: [u8; 128],
22330 #[doc = "Parameter type."]
22331 pub param_type: MavParamExtType,
22332 #[doc = "Result code."]
22333 pub param_result: ParamAck,
22334}
22335impl PARAM_EXT_ACK_DATA {
22336 pub const ENCODED_LEN: usize = 146usize;
22337 pub const DEFAULT: Self = Self {
22338 param_id: [0_u8; 16usize],
22339 param_value: [0_u8; 128usize],
22340 param_type: MavParamExtType::DEFAULT,
22341 param_result: ParamAck::DEFAULT,
22342 };
22343 #[cfg(feature = "arbitrary")]
22344 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22345 use arbitrary::{Arbitrary, Unstructured};
22346 let mut buf = [0u8; 1024];
22347 rng.fill_bytes(&mut buf);
22348 let mut unstructured = Unstructured::new(&buf);
22349 Self::arbitrary(&mut unstructured).unwrap_or_default()
22350 }
22351}
22352impl Default for PARAM_EXT_ACK_DATA {
22353 fn default() -> Self {
22354 Self::DEFAULT.clone()
22355 }
22356}
22357impl MessageData for PARAM_EXT_ACK_DATA {
22358 type Message = MavMessage;
22359 const ID: u32 = 324u32;
22360 const NAME: &'static str = "PARAM_EXT_ACK";
22361 const EXTRA_CRC: u8 = 132u8;
22362 const ENCODED_LEN: usize = 146usize;
22363 fn deser(
22364 _version: MavlinkVersion,
22365 __input: &[u8],
22366 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22367 let avail_len = __input.len();
22368 let mut payload_buf = [0; Self::ENCODED_LEN];
22369 let mut buf = if avail_len < Self::ENCODED_LEN {
22370 payload_buf[0..avail_len].copy_from_slice(__input);
22371 Bytes::new(&payload_buf)
22372 } else {
22373 Bytes::new(__input)
22374 };
22375 let mut __struct = Self::default();
22376 for v in &mut __struct.param_id {
22377 let val = buf.get_u8();
22378 *v = val;
22379 }
22380 for v in &mut __struct.param_value {
22381 let val = buf.get_u8();
22382 *v = val;
22383 }
22384 let tmp = buf.get_u8();
22385 __struct.param_type =
22386 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22387 enum_type: "MavParamExtType",
22388 value: tmp as u32,
22389 })?;
22390 let tmp = buf.get_u8();
22391 __struct.param_result =
22392 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22393 enum_type: "ParamAck",
22394 value: tmp as u32,
22395 })?;
22396 Ok(__struct)
22397 }
22398 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22399 let mut __tmp = BytesMut::new(bytes);
22400 #[allow(clippy::absurd_extreme_comparisons)]
22401 #[allow(unused_comparisons)]
22402 if __tmp.remaining() < Self::ENCODED_LEN {
22403 panic!(
22404 "buffer is too small (need {} bytes, but got {})",
22405 Self::ENCODED_LEN,
22406 __tmp.remaining(),
22407 )
22408 }
22409 for val in &self.param_id {
22410 __tmp.put_u8(*val);
22411 }
22412 for val in &self.param_value {
22413 __tmp.put_u8(*val);
22414 }
22415 __tmp.put_u8(self.param_type as u8);
22416 __tmp.put_u8(self.param_result as u8);
22417 if matches!(version, MavlinkVersion::V2) {
22418 let len = __tmp.len();
22419 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22420 } else {
22421 __tmp.len()
22422 }
22423 }
22424}
22425#[doc = "id: 321"]
22426#[doc = "Request all parameters of this component. All parameters should be emitted in response as PARAM_EXT_VALUE."]
22427#[derive(Debug, Clone, PartialEq)]
22428#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22429#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22430pub struct PARAM_EXT_REQUEST_LIST_DATA {
22431 #[doc = "System ID"]
22432 pub target_system: u8,
22433 #[doc = "Component ID"]
22434 pub target_component: u8,
22435}
22436impl PARAM_EXT_REQUEST_LIST_DATA {
22437 pub const ENCODED_LEN: usize = 2usize;
22438 pub const DEFAULT: Self = Self {
22439 target_system: 0_u8,
22440 target_component: 0_u8,
22441 };
22442 #[cfg(feature = "arbitrary")]
22443 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22444 use arbitrary::{Arbitrary, Unstructured};
22445 let mut buf = [0u8; 1024];
22446 rng.fill_bytes(&mut buf);
22447 let mut unstructured = Unstructured::new(&buf);
22448 Self::arbitrary(&mut unstructured).unwrap_or_default()
22449 }
22450}
22451impl Default for PARAM_EXT_REQUEST_LIST_DATA {
22452 fn default() -> Self {
22453 Self::DEFAULT.clone()
22454 }
22455}
22456impl MessageData for PARAM_EXT_REQUEST_LIST_DATA {
22457 type Message = MavMessage;
22458 const ID: u32 = 321u32;
22459 const NAME: &'static str = "PARAM_EXT_REQUEST_LIST";
22460 const EXTRA_CRC: u8 = 88u8;
22461 const ENCODED_LEN: usize = 2usize;
22462 fn deser(
22463 _version: MavlinkVersion,
22464 __input: &[u8],
22465 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22466 let avail_len = __input.len();
22467 let mut payload_buf = [0; Self::ENCODED_LEN];
22468 let mut buf = if avail_len < Self::ENCODED_LEN {
22469 payload_buf[0..avail_len].copy_from_slice(__input);
22470 Bytes::new(&payload_buf)
22471 } else {
22472 Bytes::new(__input)
22473 };
22474 let mut __struct = Self::default();
22475 __struct.target_system = buf.get_u8();
22476 __struct.target_component = buf.get_u8();
22477 Ok(__struct)
22478 }
22479 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22480 let mut __tmp = BytesMut::new(bytes);
22481 #[allow(clippy::absurd_extreme_comparisons)]
22482 #[allow(unused_comparisons)]
22483 if __tmp.remaining() < Self::ENCODED_LEN {
22484 panic!(
22485 "buffer is too small (need {} bytes, but got {})",
22486 Self::ENCODED_LEN,
22487 __tmp.remaining(),
22488 )
22489 }
22490 __tmp.put_u8(self.target_system);
22491 __tmp.put_u8(self.target_component);
22492 if matches!(version, MavlinkVersion::V2) {
22493 let len = __tmp.len();
22494 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22495 } else {
22496 __tmp.len()
22497 }
22498 }
22499}
22500#[doc = "id: 320"]
22501#[doc = "Request to read the value of a parameter with either the param_id string id or param_index. PARAM_EXT_VALUE should be emitted in response."]
22502#[derive(Debug, Clone, PartialEq)]
22503#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22504#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22505pub struct PARAM_EXT_REQUEST_READ_DATA {
22506 #[doc = "Parameter index. Set to -1 to use the Parameter ID field as identifier (else param_id will be ignored)"]
22507 pub param_index: i16,
22508 #[doc = "System ID"]
22509 pub target_system: u8,
22510 #[doc = "Component ID"]
22511 pub target_component: u8,
22512 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
22513 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
22514 pub param_id: [u8; 16],
22515}
22516impl PARAM_EXT_REQUEST_READ_DATA {
22517 pub const ENCODED_LEN: usize = 20usize;
22518 pub const DEFAULT: Self = Self {
22519 param_index: 0_i16,
22520 target_system: 0_u8,
22521 target_component: 0_u8,
22522 param_id: [0_u8; 16usize],
22523 };
22524 #[cfg(feature = "arbitrary")]
22525 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22526 use arbitrary::{Arbitrary, Unstructured};
22527 let mut buf = [0u8; 1024];
22528 rng.fill_bytes(&mut buf);
22529 let mut unstructured = Unstructured::new(&buf);
22530 Self::arbitrary(&mut unstructured).unwrap_or_default()
22531 }
22532}
22533impl Default for PARAM_EXT_REQUEST_READ_DATA {
22534 fn default() -> Self {
22535 Self::DEFAULT.clone()
22536 }
22537}
22538impl MessageData for PARAM_EXT_REQUEST_READ_DATA {
22539 type Message = MavMessage;
22540 const ID: u32 = 320u32;
22541 const NAME: &'static str = "PARAM_EXT_REQUEST_READ";
22542 const EXTRA_CRC: u8 = 243u8;
22543 const ENCODED_LEN: usize = 20usize;
22544 fn deser(
22545 _version: MavlinkVersion,
22546 __input: &[u8],
22547 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22548 let avail_len = __input.len();
22549 let mut payload_buf = [0; Self::ENCODED_LEN];
22550 let mut buf = if avail_len < Self::ENCODED_LEN {
22551 payload_buf[0..avail_len].copy_from_slice(__input);
22552 Bytes::new(&payload_buf)
22553 } else {
22554 Bytes::new(__input)
22555 };
22556 let mut __struct = Self::default();
22557 __struct.param_index = buf.get_i16_le();
22558 __struct.target_system = buf.get_u8();
22559 __struct.target_component = buf.get_u8();
22560 for v in &mut __struct.param_id {
22561 let val = buf.get_u8();
22562 *v = val;
22563 }
22564 Ok(__struct)
22565 }
22566 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22567 let mut __tmp = BytesMut::new(bytes);
22568 #[allow(clippy::absurd_extreme_comparisons)]
22569 #[allow(unused_comparisons)]
22570 if __tmp.remaining() < Self::ENCODED_LEN {
22571 panic!(
22572 "buffer is too small (need {} bytes, but got {})",
22573 Self::ENCODED_LEN,
22574 __tmp.remaining(),
22575 )
22576 }
22577 __tmp.put_i16_le(self.param_index);
22578 __tmp.put_u8(self.target_system);
22579 __tmp.put_u8(self.target_component);
22580 for val in &self.param_id {
22581 __tmp.put_u8(*val);
22582 }
22583 if matches!(version, MavlinkVersion::V2) {
22584 let len = __tmp.len();
22585 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22586 } else {
22587 __tmp.len()
22588 }
22589 }
22590}
22591#[doc = "id: 323"]
22592#[doc = "Set a parameter value. In order to deal with message loss (and retransmission of PARAM_EXT_SET), when setting a parameter value and the new value is the same as the current value, you will immediately get a PARAM_ACK_ACCEPTED response. If the current state is PARAM_ACK_IN_PROGRESS, you will accordingly receive a PARAM_ACK_IN_PROGRESS in response."]
22593#[derive(Debug, Clone, PartialEq)]
22594#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22595#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22596pub struct PARAM_EXT_SET_DATA {
22597 #[doc = "System ID"]
22598 pub target_system: u8,
22599 #[doc = "Component ID"]
22600 pub target_component: u8,
22601 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
22602 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
22603 pub param_id: [u8; 16],
22604 #[doc = "Parameter value"]
22605 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
22606 pub param_value: [u8; 128],
22607 #[doc = "Parameter type."]
22608 pub param_type: MavParamExtType,
22609}
22610impl PARAM_EXT_SET_DATA {
22611 pub const ENCODED_LEN: usize = 147usize;
22612 pub const DEFAULT: Self = Self {
22613 target_system: 0_u8,
22614 target_component: 0_u8,
22615 param_id: [0_u8; 16usize],
22616 param_value: [0_u8; 128usize],
22617 param_type: MavParamExtType::DEFAULT,
22618 };
22619 #[cfg(feature = "arbitrary")]
22620 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22621 use arbitrary::{Arbitrary, Unstructured};
22622 let mut buf = [0u8; 1024];
22623 rng.fill_bytes(&mut buf);
22624 let mut unstructured = Unstructured::new(&buf);
22625 Self::arbitrary(&mut unstructured).unwrap_or_default()
22626 }
22627}
22628impl Default for PARAM_EXT_SET_DATA {
22629 fn default() -> Self {
22630 Self::DEFAULT.clone()
22631 }
22632}
22633impl MessageData for PARAM_EXT_SET_DATA {
22634 type Message = MavMessage;
22635 const ID: u32 = 323u32;
22636 const NAME: &'static str = "PARAM_EXT_SET";
22637 const EXTRA_CRC: u8 = 78u8;
22638 const ENCODED_LEN: usize = 147usize;
22639 fn deser(
22640 _version: MavlinkVersion,
22641 __input: &[u8],
22642 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22643 let avail_len = __input.len();
22644 let mut payload_buf = [0; Self::ENCODED_LEN];
22645 let mut buf = if avail_len < Self::ENCODED_LEN {
22646 payload_buf[0..avail_len].copy_from_slice(__input);
22647 Bytes::new(&payload_buf)
22648 } else {
22649 Bytes::new(__input)
22650 };
22651 let mut __struct = Self::default();
22652 __struct.target_system = buf.get_u8();
22653 __struct.target_component = buf.get_u8();
22654 for v in &mut __struct.param_id {
22655 let val = buf.get_u8();
22656 *v = val;
22657 }
22658 for v in &mut __struct.param_value {
22659 let val = buf.get_u8();
22660 *v = val;
22661 }
22662 let tmp = buf.get_u8();
22663 __struct.param_type =
22664 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22665 enum_type: "MavParamExtType",
22666 value: tmp as u32,
22667 })?;
22668 Ok(__struct)
22669 }
22670 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22671 let mut __tmp = BytesMut::new(bytes);
22672 #[allow(clippy::absurd_extreme_comparisons)]
22673 #[allow(unused_comparisons)]
22674 if __tmp.remaining() < Self::ENCODED_LEN {
22675 panic!(
22676 "buffer is too small (need {} bytes, but got {})",
22677 Self::ENCODED_LEN,
22678 __tmp.remaining(),
22679 )
22680 }
22681 __tmp.put_u8(self.target_system);
22682 __tmp.put_u8(self.target_component);
22683 for val in &self.param_id {
22684 __tmp.put_u8(*val);
22685 }
22686 for val in &self.param_value {
22687 __tmp.put_u8(*val);
22688 }
22689 __tmp.put_u8(self.param_type as u8);
22690 if matches!(version, MavlinkVersion::V2) {
22691 let len = __tmp.len();
22692 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22693 } else {
22694 __tmp.len()
22695 }
22696 }
22697}
22698#[doc = "id: 322"]
22699#[doc = "Emit the value of a parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows them to re-request missing parameters after a loss or timeout."]
22700#[derive(Debug, Clone, PartialEq)]
22701#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22702#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22703pub struct PARAM_EXT_VALUE_DATA {
22704 #[doc = "Total number of parameters"]
22705 pub param_count: u16,
22706 #[doc = "Index of this parameter"]
22707 pub param_index: u16,
22708 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
22709 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
22710 pub param_id: [u8; 16],
22711 #[doc = "Parameter value"]
22712 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
22713 pub param_value: [u8; 128],
22714 #[doc = "Parameter type."]
22715 pub param_type: MavParamExtType,
22716}
22717impl PARAM_EXT_VALUE_DATA {
22718 pub const ENCODED_LEN: usize = 149usize;
22719 pub const DEFAULT: Self = Self {
22720 param_count: 0_u16,
22721 param_index: 0_u16,
22722 param_id: [0_u8; 16usize],
22723 param_value: [0_u8; 128usize],
22724 param_type: MavParamExtType::DEFAULT,
22725 };
22726 #[cfg(feature = "arbitrary")]
22727 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22728 use arbitrary::{Arbitrary, Unstructured};
22729 let mut buf = [0u8; 1024];
22730 rng.fill_bytes(&mut buf);
22731 let mut unstructured = Unstructured::new(&buf);
22732 Self::arbitrary(&mut unstructured).unwrap_or_default()
22733 }
22734}
22735impl Default for PARAM_EXT_VALUE_DATA {
22736 fn default() -> Self {
22737 Self::DEFAULT.clone()
22738 }
22739}
22740impl MessageData for PARAM_EXT_VALUE_DATA {
22741 type Message = MavMessage;
22742 const ID: u32 = 322u32;
22743 const NAME: &'static str = "PARAM_EXT_VALUE";
22744 const EXTRA_CRC: u8 = 243u8;
22745 const ENCODED_LEN: usize = 149usize;
22746 fn deser(
22747 _version: MavlinkVersion,
22748 __input: &[u8],
22749 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22750 let avail_len = __input.len();
22751 let mut payload_buf = [0; Self::ENCODED_LEN];
22752 let mut buf = if avail_len < Self::ENCODED_LEN {
22753 payload_buf[0..avail_len].copy_from_slice(__input);
22754 Bytes::new(&payload_buf)
22755 } else {
22756 Bytes::new(__input)
22757 };
22758 let mut __struct = Self::default();
22759 __struct.param_count = buf.get_u16_le();
22760 __struct.param_index = buf.get_u16_le();
22761 for v in &mut __struct.param_id {
22762 let val = buf.get_u8();
22763 *v = val;
22764 }
22765 for v in &mut __struct.param_value {
22766 let val = buf.get_u8();
22767 *v = val;
22768 }
22769 let tmp = buf.get_u8();
22770 __struct.param_type =
22771 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22772 enum_type: "MavParamExtType",
22773 value: tmp as u32,
22774 })?;
22775 Ok(__struct)
22776 }
22777 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22778 let mut __tmp = BytesMut::new(bytes);
22779 #[allow(clippy::absurd_extreme_comparisons)]
22780 #[allow(unused_comparisons)]
22781 if __tmp.remaining() < Self::ENCODED_LEN {
22782 panic!(
22783 "buffer is too small (need {} bytes, but got {})",
22784 Self::ENCODED_LEN,
22785 __tmp.remaining(),
22786 )
22787 }
22788 __tmp.put_u16_le(self.param_count);
22789 __tmp.put_u16_le(self.param_index);
22790 for val in &self.param_id {
22791 __tmp.put_u8(*val);
22792 }
22793 for val in &self.param_value {
22794 __tmp.put_u8(*val);
22795 }
22796 __tmp.put_u8(self.param_type as u8);
22797 if matches!(version, MavlinkVersion::V2) {
22798 let len = __tmp.len();
22799 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22800 } else {
22801 __tmp.len()
22802 }
22803 }
22804}
22805#[doc = "id: 50"]
22806#[doc = "Bind a RC channel to a parameter. The parameter should change according to the RC channel value."]
22807#[derive(Debug, Clone, PartialEq)]
22808#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22809#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22810pub struct PARAM_MAP_RC_DATA {
22811 #[doc = "Initial parameter value"]
22812 pub param_value0: f32,
22813 #[doc = "Scale, maps the RC range [-1, 1] to a parameter value"]
22814 pub scale: f32,
22815 #[doc = "Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)"]
22816 pub param_value_min: f32,
22817 #[doc = "Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)"]
22818 pub param_value_max: f32,
22819 #[doc = "Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index."]
22820 pub param_index: i16,
22821 #[doc = "System ID"]
22822 pub target_system: u8,
22823 #[doc = "Component ID"]
22824 pub target_component: u8,
22825 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
22826 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
22827 pub param_id: [u8; 16],
22828 #[doc = "Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC."]
22829 pub parameter_rc_channel_index: u8,
22830}
22831impl PARAM_MAP_RC_DATA {
22832 pub const ENCODED_LEN: usize = 37usize;
22833 pub const DEFAULT: Self = Self {
22834 param_value0: 0.0_f32,
22835 scale: 0.0_f32,
22836 param_value_min: 0.0_f32,
22837 param_value_max: 0.0_f32,
22838 param_index: 0_i16,
22839 target_system: 0_u8,
22840 target_component: 0_u8,
22841 param_id: [0_u8; 16usize],
22842 parameter_rc_channel_index: 0_u8,
22843 };
22844 #[cfg(feature = "arbitrary")]
22845 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22846 use arbitrary::{Arbitrary, Unstructured};
22847 let mut buf = [0u8; 1024];
22848 rng.fill_bytes(&mut buf);
22849 let mut unstructured = Unstructured::new(&buf);
22850 Self::arbitrary(&mut unstructured).unwrap_or_default()
22851 }
22852}
22853impl Default for PARAM_MAP_RC_DATA {
22854 fn default() -> Self {
22855 Self::DEFAULT.clone()
22856 }
22857}
22858impl MessageData for PARAM_MAP_RC_DATA {
22859 type Message = MavMessage;
22860 const ID: u32 = 50u32;
22861 const NAME: &'static str = "PARAM_MAP_RC";
22862 const EXTRA_CRC: u8 = 78u8;
22863 const ENCODED_LEN: usize = 37usize;
22864 fn deser(
22865 _version: MavlinkVersion,
22866 __input: &[u8],
22867 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22868 let avail_len = __input.len();
22869 let mut payload_buf = [0; Self::ENCODED_LEN];
22870 let mut buf = if avail_len < Self::ENCODED_LEN {
22871 payload_buf[0..avail_len].copy_from_slice(__input);
22872 Bytes::new(&payload_buf)
22873 } else {
22874 Bytes::new(__input)
22875 };
22876 let mut __struct = Self::default();
22877 __struct.param_value0 = buf.get_f32_le();
22878 __struct.scale = buf.get_f32_le();
22879 __struct.param_value_min = buf.get_f32_le();
22880 __struct.param_value_max = buf.get_f32_le();
22881 __struct.param_index = buf.get_i16_le();
22882 __struct.target_system = buf.get_u8();
22883 __struct.target_component = buf.get_u8();
22884 for v in &mut __struct.param_id {
22885 let val = buf.get_u8();
22886 *v = val;
22887 }
22888 __struct.parameter_rc_channel_index = buf.get_u8();
22889 Ok(__struct)
22890 }
22891 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22892 let mut __tmp = BytesMut::new(bytes);
22893 #[allow(clippy::absurd_extreme_comparisons)]
22894 #[allow(unused_comparisons)]
22895 if __tmp.remaining() < Self::ENCODED_LEN {
22896 panic!(
22897 "buffer is too small (need {} bytes, but got {})",
22898 Self::ENCODED_LEN,
22899 __tmp.remaining(),
22900 )
22901 }
22902 __tmp.put_f32_le(self.param_value0);
22903 __tmp.put_f32_le(self.scale);
22904 __tmp.put_f32_le(self.param_value_min);
22905 __tmp.put_f32_le(self.param_value_max);
22906 __tmp.put_i16_le(self.param_index);
22907 __tmp.put_u8(self.target_system);
22908 __tmp.put_u8(self.target_component);
22909 for val in &self.param_id {
22910 __tmp.put_u8(*val);
22911 }
22912 __tmp.put_u8(self.parameter_rc_channel_index);
22913 if matches!(version, MavlinkVersion::V2) {
22914 let len = __tmp.len();
22915 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22916 } else {
22917 __tmp.len()
22918 }
22919 }
22920}
22921#[doc = "id: 21"]
22922#[doc = "Request all parameters of this component. After this request, all parameters are emitted. The parameter microservice is documented at <https://mavlink.io/en/services/parameter.html>."]
22923#[derive(Debug, Clone, PartialEq)]
22924#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22925#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22926pub struct PARAM_REQUEST_LIST_DATA {
22927 #[doc = "System ID"]
22928 pub target_system: u8,
22929 #[doc = "Component ID"]
22930 pub target_component: u8,
22931}
22932impl PARAM_REQUEST_LIST_DATA {
22933 pub const ENCODED_LEN: usize = 2usize;
22934 pub const DEFAULT: Self = Self {
22935 target_system: 0_u8,
22936 target_component: 0_u8,
22937 };
22938 #[cfg(feature = "arbitrary")]
22939 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22940 use arbitrary::{Arbitrary, Unstructured};
22941 let mut buf = [0u8; 1024];
22942 rng.fill_bytes(&mut buf);
22943 let mut unstructured = Unstructured::new(&buf);
22944 Self::arbitrary(&mut unstructured).unwrap_or_default()
22945 }
22946}
22947impl Default for PARAM_REQUEST_LIST_DATA {
22948 fn default() -> Self {
22949 Self::DEFAULT.clone()
22950 }
22951}
22952impl MessageData for PARAM_REQUEST_LIST_DATA {
22953 type Message = MavMessage;
22954 const ID: u32 = 21u32;
22955 const NAME: &'static str = "PARAM_REQUEST_LIST";
22956 const EXTRA_CRC: u8 = 159u8;
22957 const ENCODED_LEN: usize = 2usize;
22958 fn deser(
22959 _version: MavlinkVersion,
22960 __input: &[u8],
22961 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22962 let avail_len = __input.len();
22963 let mut payload_buf = [0; Self::ENCODED_LEN];
22964 let mut buf = if avail_len < Self::ENCODED_LEN {
22965 payload_buf[0..avail_len].copy_from_slice(__input);
22966 Bytes::new(&payload_buf)
22967 } else {
22968 Bytes::new(__input)
22969 };
22970 let mut __struct = Self::default();
22971 __struct.target_system = buf.get_u8();
22972 __struct.target_component = buf.get_u8();
22973 Ok(__struct)
22974 }
22975 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22976 let mut __tmp = BytesMut::new(bytes);
22977 #[allow(clippy::absurd_extreme_comparisons)]
22978 #[allow(unused_comparisons)]
22979 if __tmp.remaining() < Self::ENCODED_LEN {
22980 panic!(
22981 "buffer is too small (need {} bytes, but got {})",
22982 Self::ENCODED_LEN,
22983 __tmp.remaining(),
22984 )
22985 }
22986 __tmp.put_u8(self.target_system);
22987 __tmp.put_u8(self.target_component);
22988 if matches!(version, MavlinkVersion::V2) {
22989 let len = __tmp.len();
22990 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22991 } else {
22992 __tmp.len()
22993 }
22994 }
22995}
22996#[doc = "id: 20"]
22997#[doc = "value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also <https://mavlink.io/en/services/parameter.html> for a full documentation of QGroundControl and IMU code."]
22998#[derive(Debug, Clone, PartialEq)]
22999#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23000#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23001pub struct PARAM_REQUEST_READ_DATA {
23002 #[doc = "Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)"]
23003 pub param_index: i16,
23004 #[doc = "System ID"]
23005 pub target_system: u8,
23006 #[doc = "Component ID"]
23007 pub target_component: u8,
23008 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
23009 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23010 pub param_id: [u8; 16],
23011}
23012impl PARAM_REQUEST_READ_DATA {
23013 pub const ENCODED_LEN: usize = 20usize;
23014 pub const DEFAULT: Self = Self {
23015 param_index: 0_i16,
23016 target_system: 0_u8,
23017 target_component: 0_u8,
23018 param_id: [0_u8; 16usize],
23019 };
23020 #[cfg(feature = "arbitrary")]
23021 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23022 use arbitrary::{Arbitrary, Unstructured};
23023 let mut buf = [0u8; 1024];
23024 rng.fill_bytes(&mut buf);
23025 let mut unstructured = Unstructured::new(&buf);
23026 Self::arbitrary(&mut unstructured).unwrap_or_default()
23027 }
23028}
23029impl Default for PARAM_REQUEST_READ_DATA {
23030 fn default() -> Self {
23031 Self::DEFAULT.clone()
23032 }
23033}
23034impl MessageData for PARAM_REQUEST_READ_DATA {
23035 type Message = MavMessage;
23036 const ID: u32 = 20u32;
23037 const NAME: &'static str = "PARAM_REQUEST_READ";
23038 const EXTRA_CRC: u8 = 214u8;
23039 const ENCODED_LEN: usize = 20usize;
23040 fn deser(
23041 _version: MavlinkVersion,
23042 __input: &[u8],
23043 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23044 let avail_len = __input.len();
23045 let mut payload_buf = [0; Self::ENCODED_LEN];
23046 let mut buf = if avail_len < Self::ENCODED_LEN {
23047 payload_buf[0..avail_len].copy_from_slice(__input);
23048 Bytes::new(&payload_buf)
23049 } else {
23050 Bytes::new(__input)
23051 };
23052 let mut __struct = Self::default();
23053 __struct.param_index = buf.get_i16_le();
23054 __struct.target_system = buf.get_u8();
23055 __struct.target_component = buf.get_u8();
23056 for v in &mut __struct.param_id {
23057 let val = buf.get_u8();
23058 *v = val;
23059 }
23060 Ok(__struct)
23061 }
23062 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23063 let mut __tmp = BytesMut::new(bytes);
23064 #[allow(clippy::absurd_extreme_comparisons)]
23065 #[allow(unused_comparisons)]
23066 if __tmp.remaining() < Self::ENCODED_LEN {
23067 panic!(
23068 "buffer is too small (need {} bytes, but got {})",
23069 Self::ENCODED_LEN,
23070 __tmp.remaining(),
23071 )
23072 }
23073 __tmp.put_i16_le(self.param_index);
23074 __tmp.put_u8(self.target_system);
23075 __tmp.put_u8(self.target_component);
23076 for val in &self.param_id {
23077 __tmp.put_u8(*val);
23078 }
23079 if matches!(version, MavlinkVersion::V2) {
23080 let len = __tmp.len();
23081 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23082 } else {
23083 __tmp.len()
23084 }
23085 }
23086}
23087#[doc = "id: 23"]
23088#[doc = "Set a parameter value (write new value to permanent storage). The receiving component should acknowledge the new parameter value by broadcasting a PARAM_VALUE message (broadcasting ensures that multiple GCS all have an up-to-date list of all parameters). If the sending GCS did not receive a PARAM_VALUE within its timeout time, it should re-send the PARAM_SET message. The parameter microservice is documented at <https://mavlink.io/en/services/parameter.html>."]
23089#[derive(Debug, Clone, PartialEq)]
23090#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23091#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23092pub struct PARAM_SET_DATA {
23093 #[doc = "Onboard parameter value"]
23094 pub param_value: f32,
23095 #[doc = "System ID"]
23096 pub target_system: u8,
23097 #[doc = "Component ID"]
23098 pub target_component: u8,
23099 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
23100 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23101 pub param_id: [u8; 16],
23102 #[doc = "Onboard parameter type."]
23103 pub param_type: MavParamType,
23104}
23105impl PARAM_SET_DATA {
23106 pub const ENCODED_LEN: usize = 23usize;
23107 pub const DEFAULT: Self = Self {
23108 param_value: 0.0_f32,
23109 target_system: 0_u8,
23110 target_component: 0_u8,
23111 param_id: [0_u8; 16usize],
23112 param_type: MavParamType::DEFAULT,
23113 };
23114 #[cfg(feature = "arbitrary")]
23115 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23116 use arbitrary::{Arbitrary, Unstructured};
23117 let mut buf = [0u8; 1024];
23118 rng.fill_bytes(&mut buf);
23119 let mut unstructured = Unstructured::new(&buf);
23120 Self::arbitrary(&mut unstructured).unwrap_or_default()
23121 }
23122}
23123impl Default for PARAM_SET_DATA {
23124 fn default() -> Self {
23125 Self::DEFAULT.clone()
23126 }
23127}
23128impl MessageData for PARAM_SET_DATA {
23129 type Message = MavMessage;
23130 const ID: u32 = 23u32;
23131 const NAME: &'static str = "PARAM_SET";
23132 const EXTRA_CRC: u8 = 168u8;
23133 const ENCODED_LEN: usize = 23usize;
23134 fn deser(
23135 _version: MavlinkVersion,
23136 __input: &[u8],
23137 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23138 let avail_len = __input.len();
23139 let mut payload_buf = [0; Self::ENCODED_LEN];
23140 let mut buf = if avail_len < Self::ENCODED_LEN {
23141 payload_buf[0..avail_len].copy_from_slice(__input);
23142 Bytes::new(&payload_buf)
23143 } else {
23144 Bytes::new(__input)
23145 };
23146 let mut __struct = Self::default();
23147 __struct.param_value = buf.get_f32_le();
23148 __struct.target_system = buf.get_u8();
23149 __struct.target_component = buf.get_u8();
23150 for v in &mut __struct.param_id {
23151 let val = buf.get_u8();
23152 *v = val;
23153 }
23154 let tmp = buf.get_u8();
23155 __struct.param_type =
23156 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23157 enum_type: "MavParamType",
23158 value: tmp as u32,
23159 })?;
23160 Ok(__struct)
23161 }
23162 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23163 let mut __tmp = BytesMut::new(bytes);
23164 #[allow(clippy::absurd_extreme_comparisons)]
23165 #[allow(unused_comparisons)]
23166 if __tmp.remaining() < Self::ENCODED_LEN {
23167 panic!(
23168 "buffer is too small (need {} bytes, but got {})",
23169 Self::ENCODED_LEN,
23170 __tmp.remaining(),
23171 )
23172 }
23173 __tmp.put_f32_le(self.param_value);
23174 __tmp.put_u8(self.target_system);
23175 __tmp.put_u8(self.target_component);
23176 for val in &self.param_id {
23177 __tmp.put_u8(*val);
23178 }
23179 __tmp.put_u8(self.param_type as u8);
23180 if matches!(version, MavlinkVersion::V2) {
23181 let len = __tmp.len();
23182 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23183 } else {
23184 __tmp.len()
23185 }
23186 }
23187}
23188#[doc = "id: 22"]
23189#[doc = "Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. The parameter microservice is documented at <https://mavlink.io/en/services/parameter.html>."]
23190#[derive(Debug, Clone, PartialEq)]
23191#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23192#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23193pub struct PARAM_VALUE_DATA {
23194 #[doc = "Onboard parameter value"]
23195 pub param_value: f32,
23196 #[doc = "Total number of onboard parameters"]
23197 pub param_count: u16,
23198 #[doc = "Index of this onboard parameter"]
23199 pub param_index: u16,
23200 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
23201 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23202 pub param_id: [u8; 16],
23203 #[doc = "Onboard parameter type."]
23204 pub param_type: MavParamType,
23205}
23206impl PARAM_VALUE_DATA {
23207 pub const ENCODED_LEN: usize = 25usize;
23208 pub const DEFAULT: Self = Self {
23209 param_value: 0.0_f32,
23210 param_count: 0_u16,
23211 param_index: 0_u16,
23212 param_id: [0_u8; 16usize],
23213 param_type: MavParamType::DEFAULT,
23214 };
23215 #[cfg(feature = "arbitrary")]
23216 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23217 use arbitrary::{Arbitrary, Unstructured};
23218 let mut buf = [0u8; 1024];
23219 rng.fill_bytes(&mut buf);
23220 let mut unstructured = Unstructured::new(&buf);
23221 Self::arbitrary(&mut unstructured).unwrap_or_default()
23222 }
23223}
23224impl Default for PARAM_VALUE_DATA {
23225 fn default() -> Self {
23226 Self::DEFAULT.clone()
23227 }
23228}
23229impl MessageData for PARAM_VALUE_DATA {
23230 type Message = MavMessage;
23231 const ID: u32 = 22u32;
23232 const NAME: &'static str = "PARAM_VALUE";
23233 const EXTRA_CRC: u8 = 220u8;
23234 const ENCODED_LEN: usize = 25usize;
23235 fn deser(
23236 _version: MavlinkVersion,
23237 __input: &[u8],
23238 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23239 let avail_len = __input.len();
23240 let mut payload_buf = [0; Self::ENCODED_LEN];
23241 let mut buf = if avail_len < Self::ENCODED_LEN {
23242 payload_buf[0..avail_len].copy_from_slice(__input);
23243 Bytes::new(&payload_buf)
23244 } else {
23245 Bytes::new(__input)
23246 };
23247 let mut __struct = Self::default();
23248 __struct.param_value = buf.get_f32_le();
23249 __struct.param_count = buf.get_u16_le();
23250 __struct.param_index = buf.get_u16_le();
23251 for v in &mut __struct.param_id {
23252 let val = buf.get_u8();
23253 *v = val;
23254 }
23255 let tmp = buf.get_u8();
23256 __struct.param_type =
23257 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23258 enum_type: "MavParamType",
23259 value: tmp as u32,
23260 })?;
23261 Ok(__struct)
23262 }
23263 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23264 let mut __tmp = BytesMut::new(bytes);
23265 #[allow(clippy::absurd_extreme_comparisons)]
23266 #[allow(unused_comparisons)]
23267 if __tmp.remaining() < Self::ENCODED_LEN {
23268 panic!(
23269 "buffer is too small (need {} bytes, but got {})",
23270 Self::ENCODED_LEN,
23271 __tmp.remaining(),
23272 )
23273 }
23274 __tmp.put_f32_le(self.param_value);
23275 __tmp.put_u16_le(self.param_count);
23276 __tmp.put_u16_le(self.param_index);
23277 for val in &self.param_id {
23278 __tmp.put_u8(*val);
23279 }
23280 __tmp.put_u8(self.param_type as u8);
23281 if matches!(version, MavlinkVersion::V2) {
23282 let len = __tmp.len();
23283 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23284 } else {
23285 __tmp.len()
23286 }
23287 }
23288}
23289#[doc = "id: 4"]
23290#[doc = "A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. The ping microservice is documented at <https://mavlink.io/en/services/ping.html>."]
23291#[derive(Debug, Clone, PartialEq)]
23292#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23293#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23294pub struct PING_DATA {
23295 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
23296 pub time_usec: u64,
23297 #[doc = "PING sequence"]
23298 pub seq: u32,
23299 #[doc = "0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system"]
23300 pub target_system: u8,
23301 #[doc = "0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component."]
23302 pub target_component: u8,
23303}
23304impl PING_DATA {
23305 pub const ENCODED_LEN: usize = 14usize;
23306 pub const DEFAULT: Self = Self {
23307 time_usec: 0_u64,
23308 seq: 0_u32,
23309 target_system: 0_u8,
23310 target_component: 0_u8,
23311 };
23312 #[cfg(feature = "arbitrary")]
23313 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23314 use arbitrary::{Arbitrary, Unstructured};
23315 let mut buf = [0u8; 1024];
23316 rng.fill_bytes(&mut buf);
23317 let mut unstructured = Unstructured::new(&buf);
23318 Self::arbitrary(&mut unstructured).unwrap_or_default()
23319 }
23320}
23321impl Default for PING_DATA {
23322 fn default() -> Self {
23323 Self::DEFAULT.clone()
23324 }
23325}
23326impl MessageData for PING_DATA {
23327 type Message = MavMessage;
23328 const ID: u32 = 4u32;
23329 const NAME: &'static str = "PING";
23330 const EXTRA_CRC: u8 = 237u8;
23331 const ENCODED_LEN: usize = 14usize;
23332 fn deser(
23333 _version: MavlinkVersion,
23334 __input: &[u8],
23335 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23336 let avail_len = __input.len();
23337 let mut payload_buf = [0; Self::ENCODED_LEN];
23338 let mut buf = if avail_len < Self::ENCODED_LEN {
23339 payload_buf[0..avail_len].copy_from_slice(__input);
23340 Bytes::new(&payload_buf)
23341 } else {
23342 Bytes::new(__input)
23343 };
23344 let mut __struct = Self::default();
23345 __struct.time_usec = buf.get_u64_le();
23346 __struct.seq = buf.get_u32_le();
23347 __struct.target_system = buf.get_u8();
23348 __struct.target_component = buf.get_u8();
23349 Ok(__struct)
23350 }
23351 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23352 let mut __tmp = BytesMut::new(bytes);
23353 #[allow(clippy::absurd_extreme_comparisons)]
23354 #[allow(unused_comparisons)]
23355 if __tmp.remaining() < Self::ENCODED_LEN {
23356 panic!(
23357 "buffer is too small (need {} bytes, but got {})",
23358 Self::ENCODED_LEN,
23359 __tmp.remaining(),
23360 )
23361 }
23362 __tmp.put_u64_le(self.time_usec);
23363 __tmp.put_u32_le(self.seq);
23364 __tmp.put_u8(self.target_system);
23365 __tmp.put_u8(self.target_component);
23366 if matches!(version, MavlinkVersion::V2) {
23367 let len = __tmp.len();
23368 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23369 } else {
23370 __tmp.len()
23371 }
23372 }
23373}
23374#[doc = "id: 258"]
23375#[doc = "Control vehicle tone generation (buzzer)."]
23376#[derive(Debug, Clone, PartialEq)]
23377#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23378#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23379pub struct PLAY_TUNE_DATA {
23380 #[doc = "System ID"]
23381 pub target_system: u8,
23382 #[doc = "Component ID"]
23383 pub target_component: u8,
23384 #[doc = "tune in board specific format"]
23385 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23386 pub tune: [u8; 30],
23387 #[doc = "tune extension (appended to tune)"]
23388 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23389 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23390 pub tune2: [u8; 200],
23391}
23392impl PLAY_TUNE_DATA {
23393 pub const ENCODED_LEN: usize = 232usize;
23394 pub const DEFAULT: Self = Self {
23395 target_system: 0_u8,
23396 target_component: 0_u8,
23397 tune: [0_u8; 30usize],
23398 tune2: [0_u8; 200usize],
23399 };
23400 #[cfg(feature = "arbitrary")]
23401 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23402 use arbitrary::{Arbitrary, Unstructured};
23403 let mut buf = [0u8; 1024];
23404 rng.fill_bytes(&mut buf);
23405 let mut unstructured = Unstructured::new(&buf);
23406 Self::arbitrary(&mut unstructured).unwrap_or_default()
23407 }
23408}
23409impl Default for PLAY_TUNE_DATA {
23410 fn default() -> Self {
23411 Self::DEFAULT.clone()
23412 }
23413}
23414impl MessageData for PLAY_TUNE_DATA {
23415 type Message = MavMessage;
23416 const ID: u32 = 258u32;
23417 const NAME: &'static str = "PLAY_TUNE";
23418 const EXTRA_CRC: u8 = 187u8;
23419 const ENCODED_LEN: usize = 232usize;
23420 fn deser(
23421 _version: MavlinkVersion,
23422 __input: &[u8],
23423 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23424 let avail_len = __input.len();
23425 let mut payload_buf = [0; Self::ENCODED_LEN];
23426 let mut buf = if avail_len < Self::ENCODED_LEN {
23427 payload_buf[0..avail_len].copy_from_slice(__input);
23428 Bytes::new(&payload_buf)
23429 } else {
23430 Bytes::new(__input)
23431 };
23432 let mut __struct = Self::default();
23433 __struct.target_system = buf.get_u8();
23434 __struct.target_component = buf.get_u8();
23435 for v in &mut __struct.tune {
23436 let val = buf.get_u8();
23437 *v = val;
23438 }
23439 for v in &mut __struct.tune2 {
23440 let val = buf.get_u8();
23441 *v = val;
23442 }
23443 Ok(__struct)
23444 }
23445 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23446 let mut __tmp = BytesMut::new(bytes);
23447 #[allow(clippy::absurd_extreme_comparisons)]
23448 #[allow(unused_comparisons)]
23449 if __tmp.remaining() < Self::ENCODED_LEN {
23450 panic!(
23451 "buffer is too small (need {} bytes, but got {})",
23452 Self::ENCODED_LEN,
23453 __tmp.remaining(),
23454 )
23455 }
23456 __tmp.put_u8(self.target_system);
23457 __tmp.put_u8(self.target_component);
23458 for val in &self.tune {
23459 __tmp.put_u8(*val);
23460 }
23461 for val in &self.tune2 {
23462 __tmp.put_u8(*val);
23463 }
23464 if matches!(version, MavlinkVersion::V2) {
23465 let len = __tmp.len();
23466 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23467 } else {
23468 __tmp.len()
23469 }
23470 }
23471}
23472#[doc = "id: 400"]
23473#[doc = "Play vehicle tone/tune (buzzer). Supersedes message PLAY_TUNE."]
23474#[derive(Debug, Clone, PartialEq)]
23475#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23476#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23477pub struct PLAY_TUNE_V2_DATA {
23478 #[doc = "Tune format"]
23479 pub format: TuneFormat,
23480 #[doc = "System ID"]
23481 pub target_system: u8,
23482 #[doc = "Component ID"]
23483 pub target_component: u8,
23484 #[doc = "Tune definition as a NULL-terminated string."]
23485 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23486 pub tune: [u8; 248],
23487}
23488impl PLAY_TUNE_V2_DATA {
23489 pub const ENCODED_LEN: usize = 254usize;
23490 pub const DEFAULT: Self = Self {
23491 format: TuneFormat::DEFAULT,
23492 target_system: 0_u8,
23493 target_component: 0_u8,
23494 tune: [0_u8; 248usize],
23495 };
23496 #[cfg(feature = "arbitrary")]
23497 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23498 use arbitrary::{Arbitrary, Unstructured};
23499 let mut buf = [0u8; 1024];
23500 rng.fill_bytes(&mut buf);
23501 let mut unstructured = Unstructured::new(&buf);
23502 Self::arbitrary(&mut unstructured).unwrap_or_default()
23503 }
23504}
23505impl Default for PLAY_TUNE_V2_DATA {
23506 fn default() -> Self {
23507 Self::DEFAULT.clone()
23508 }
23509}
23510impl MessageData for PLAY_TUNE_V2_DATA {
23511 type Message = MavMessage;
23512 const ID: u32 = 400u32;
23513 const NAME: &'static str = "PLAY_TUNE_V2";
23514 const EXTRA_CRC: u8 = 110u8;
23515 const ENCODED_LEN: usize = 254usize;
23516 fn deser(
23517 _version: MavlinkVersion,
23518 __input: &[u8],
23519 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23520 let avail_len = __input.len();
23521 let mut payload_buf = [0; Self::ENCODED_LEN];
23522 let mut buf = if avail_len < Self::ENCODED_LEN {
23523 payload_buf[0..avail_len].copy_from_slice(__input);
23524 Bytes::new(&payload_buf)
23525 } else {
23526 Bytes::new(__input)
23527 };
23528 let mut __struct = Self::default();
23529 let tmp = buf.get_u32_le();
23530 __struct.format = FromPrimitive::from_u32(tmp).ok_or(
23531 ::mavlink_core::error::ParserError::InvalidEnum {
23532 enum_type: "TuneFormat",
23533 value: tmp as u32,
23534 },
23535 )?;
23536 __struct.target_system = buf.get_u8();
23537 __struct.target_component = buf.get_u8();
23538 for v in &mut __struct.tune {
23539 let val = buf.get_u8();
23540 *v = val;
23541 }
23542 Ok(__struct)
23543 }
23544 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23545 let mut __tmp = BytesMut::new(bytes);
23546 #[allow(clippy::absurd_extreme_comparisons)]
23547 #[allow(unused_comparisons)]
23548 if __tmp.remaining() < Self::ENCODED_LEN {
23549 panic!(
23550 "buffer is too small (need {} bytes, but got {})",
23551 Self::ENCODED_LEN,
23552 __tmp.remaining(),
23553 )
23554 }
23555 __tmp.put_u32_le(self.format as u32);
23556 __tmp.put_u8(self.target_system);
23557 __tmp.put_u8(self.target_component);
23558 for val in &self.tune {
23559 __tmp.put_u8(*val);
23560 }
23561 if matches!(version, MavlinkVersion::V2) {
23562 let len = __tmp.len();
23563 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23564 } else {
23565 __tmp.len()
23566 }
23567 }
23568}
23569#[doc = "id: 87"]
23570#[doc = "Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way."]
23571#[derive(Debug, Clone, PartialEq)]
23572#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23573#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23574pub struct POSITION_TARGET_GLOBAL_INT_DATA {
23575 #[doc = "Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency."]
23576 pub time_boot_ms: u32,
23577 #[doc = "Latitude in WGS84 frame"]
23578 pub lat_int: i32,
23579 #[doc = "Longitude in WGS84 frame"]
23580 pub lon_int: i32,
23581 #[doc = "Altitude (MSL, AGL or relative to home altitude, depending on frame)"]
23582 pub alt: f32,
23583 #[doc = "X velocity in NED frame"]
23584 pub vx: f32,
23585 #[doc = "Y velocity in NED frame"]
23586 pub vy: f32,
23587 #[doc = "Z velocity in NED frame"]
23588 pub vz: f32,
23589 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
23590 pub afx: f32,
23591 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
23592 pub afy: f32,
23593 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
23594 pub afz: f32,
23595 #[doc = "yaw setpoint"]
23596 pub yaw: f32,
23597 #[doc = "yaw rate setpoint"]
23598 pub yaw_rate: f32,
23599 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
23600 pub type_mask: PositionTargetTypemask,
23601 #[doc = "Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated)"]
23602 pub coordinate_frame: MavFrame,
23603}
23604impl POSITION_TARGET_GLOBAL_INT_DATA {
23605 pub const ENCODED_LEN: usize = 51usize;
23606 pub const DEFAULT: Self = Self {
23607 time_boot_ms: 0_u32,
23608 lat_int: 0_i32,
23609 lon_int: 0_i32,
23610 alt: 0.0_f32,
23611 vx: 0.0_f32,
23612 vy: 0.0_f32,
23613 vz: 0.0_f32,
23614 afx: 0.0_f32,
23615 afy: 0.0_f32,
23616 afz: 0.0_f32,
23617 yaw: 0.0_f32,
23618 yaw_rate: 0.0_f32,
23619 type_mask: PositionTargetTypemask::DEFAULT,
23620 coordinate_frame: MavFrame::DEFAULT,
23621 };
23622 #[cfg(feature = "arbitrary")]
23623 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23624 use arbitrary::{Arbitrary, Unstructured};
23625 let mut buf = [0u8; 1024];
23626 rng.fill_bytes(&mut buf);
23627 let mut unstructured = Unstructured::new(&buf);
23628 Self::arbitrary(&mut unstructured).unwrap_or_default()
23629 }
23630}
23631impl Default for POSITION_TARGET_GLOBAL_INT_DATA {
23632 fn default() -> Self {
23633 Self::DEFAULT.clone()
23634 }
23635}
23636impl MessageData for POSITION_TARGET_GLOBAL_INT_DATA {
23637 type Message = MavMessage;
23638 const ID: u32 = 87u32;
23639 const NAME: &'static str = "POSITION_TARGET_GLOBAL_INT";
23640 const EXTRA_CRC: u8 = 150u8;
23641 const ENCODED_LEN: usize = 51usize;
23642 fn deser(
23643 _version: MavlinkVersion,
23644 __input: &[u8],
23645 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23646 let avail_len = __input.len();
23647 let mut payload_buf = [0; Self::ENCODED_LEN];
23648 let mut buf = if avail_len < Self::ENCODED_LEN {
23649 payload_buf[0..avail_len].copy_from_slice(__input);
23650 Bytes::new(&payload_buf)
23651 } else {
23652 Bytes::new(__input)
23653 };
23654 let mut __struct = Self::default();
23655 __struct.time_boot_ms = buf.get_u32_le();
23656 __struct.lat_int = buf.get_i32_le();
23657 __struct.lon_int = buf.get_i32_le();
23658 __struct.alt = buf.get_f32_le();
23659 __struct.vx = buf.get_f32_le();
23660 __struct.vy = buf.get_f32_le();
23661 __struct.vz = buf.get_f32_le();
23662 __struct.afx = buf.get_f32_le();
23663 __struct.afy = buf.get_f32_le();
23664 __struct.afz = buf.get_f32_le();
23665 __struct.yaw = buf.get_f32_le();
23666 __struct.yaw_rate = buf.get_f32_le();
23667 let tmp = buf.get_u16_le();
23668 __struct.type_mask = PositionTargetTypemask::from_bits(
23669 tmp & PositionTargetTypemask::all().bits(),
23670 )
23671 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
23672 flag_type: "PositionTargetTypemask",
23673 value: tmp as u32,
23674 })?;
23675 let tmp = buf.get_u8();
23676 __struct.coordinate_frame =
23677 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23678 enum_type: "MavFrame",
23679 value: tmp as u32,
23680 })?;
23681 Ok(__struct)
23682 }
23683 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23684 let mut __tmp = BytesMut::new(bytes);
23685 #[allow(clippy::absurd_extreme_comparisons)]
23686 #[allow(unused_comparisons)]
23687 if __tmp.remaining() < Self::ENCODED_LEN {
23688 panic!(
23689 "buffer is too small (need {} bytes, but got {})",
23690 Self::ENCODED_LEN,
23691 __tmp.remaining(),
23692 )
23693 }
23694 __tmp.put_u32_le(self.time_boot_ms);
23695 __tmp.put_i32_le(self.lat_int);
23696 __tmp.put_i32_le(self.lon_int);
23697 __tmp.put_f32_le(self.alt);
23698 __tmp.put_f32_le(self.vx);
23699 __tmp.put_f32_le(self.vy);
23700 __tmp.put_f32_le(self.vz);
23701 __tmp.put_f32_le(self.afx);
23702 __tmp.put_f32_le(self.afy);
23703 __tmp.put_f32_le(self.afz);
23704 __tmp.put_f32_le(self.yaw);
23705 __tmp.put_f32_le(self.yaw_rate);
23706 __tmp.put_u16_le(self.type_mask.bits());
23707 __tmp.put_u8(self.coordinate_frame as u8);
23708 if matches!(version, MavlinkVersion::V2) {
23709 let len = __tmp.len();
23710 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23711 } else {
23712 __tmp.len()
23713 }
23714 }
23715}
23716#[doc = "id: 85"]
23717#[doc = "Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_LOCAL_NED if the vehicle is being controlled this way."]
23718#[derive(Debug, Clone, PartialEq)]
23719#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23720#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23721pub struct POSITION_TARGET_LOCAL_NED_DATA {
23722 #[doc = "Timestamp (time since system boot)."]
23723 pub time_boot_ms: u32,
23724 #[doc = "X Position in NED frame"]
23725 pub x: f32,
23726 #[doc = "Y Position in NED frame"]
23727 pub y: f32,
23728 #[doc = "Z Position in NED frame (note, altitude is negative in NED)"]
23729 pub z: f32,
23730 #[doc = "X velocity in NED frame"]
23731 pub vx: f32,
23732 #[doc = "Y velocity in NED frame"]
23733 pub vy: f32,
23734 #[doc = "Z velocity in NED frame"]
23735 pub vz: f32,
23736 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
23737 pub afx: f32,
23738 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
23739 pub afy: f32,
23740 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
23741 pub afz: f32,
23742 #[doc = "yaw setpoint"]
23743 pub yaw: f32,
23744 #[doc = "yaw rate setpoint"]
23745 pub yaw_rate: f32,
23746 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
23747 pub type_mask: PositionTargetTypemask,
23748 #[doc = "Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9"]
23749 pub coordinate_frame: MavFrame,
23750}
23751impl POSITION_TARGET_LOCAL_NED_DATA {
23752 pub const ENCODED_LEN: usize = 51usize;
23753 pub const DEFAULT: Self = Self {
23754 time_boot_ms: 0_u32,
23755 x: 0.0_f32,
23756 y: 0.0_f32,
23757 z: 0.0_f32,
23758 vx: 0.0_f32,
23759 vy: 0.0_f32,
23760 vz: 0.0_f32,
23761 afx: 0.0_f32,
23762 afy: 0.0_f32,
23763 afz: 0.0_f32,
23764 yaw: 0.0_f32,
23765 yaw_rate: 0.0_f32,
23766 type_mask: PositionTargetTypemask::DEFAULT,
23767 coordinate_frame: MavFrame::DEFAULT,
23768 };
23769 #[cfg(feature = "arbitrary")]
23770 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23771 use arbitrary::{Arbitrary, Unstructured};
23772 let mut buf = [0u8; 1024];
23773 rng.fill_bytes(&mut buf);
23774 let mut unstructured = Unstructured::new(&buf);
23775 Self::arbitrary(&mut unstructured).unwrap_or_default()
23776 }
23777}
23778impl Default for POSITION_TARGET_LOCAL_NED_DATA {
23779 fn default() -> Self {
23780 Self::DEFAULT.clone()
23781 }
23782}
23783impl MessageData for POSITION_TARGET_LOCAL_NED_DATA {
23784 type Message = MavMessage;
23785 const ID: u32 = 85u32;
23786 const NAME: &'static str = "POSITION_TARGET_LOCAL_NED";
23787 const EXTRA_CRC: u8 = 140u8;
23788 const ENCODED_LEN: usize = 51usize;
23789 fn deser(
23790 _version: MavlinkVersion,
23791 __input: &[u8],
23792 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23793 let avail_len = __input.len();
23794 let mut payload_buf = [0; Self::ENCODED_LEN];
23795 let mut buf = if avail_len < Self::ENCODED_LEN {
23796 payload_buf[0..avail_len].copy_from_slice(__input);
23797 Bytes::new(&payload_buf)
23798 } else {
23799 Bytes::new(__input)
23800 };
23801 let mut __struct = Self::default();
23802 __struct.time_boot_ms = buf.get_u32_le();
23803 __struct.x = buf.get_f32_le();
23804 __struct.y = buf.get_f32_le();
23805 __struct.z = buf.get_f32_le();
23806 __struct.vx = buf.get_f32_le();
23807 __struct.vy = buf.get_f32_le();
23808 __struct.vz = buf.get_f32_le();
23809 __struct.afx = buf.get_f32_le();
23810 __struct.afy = buf.get_f32_le();
23811 __struct.afz = buf.get_f32_le();
23812 __struct.yaw = buf.get_f32_le();
23813 __struct.yaw_rate = buf.get_f32_le();
23814 let tmp = buf.get_u16_le();
23815 __struct.type_mask = PositionTargetTypemask::from_bits(
23816 tmp & PositionTargetTypemask::all().bits(),
23817 )
23818 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
23819 flag_type: "PositionTargetTypemask",
23820 value: tmp as u32,
23821 })?;
23822 let tmp = buf.get_u8();
23823 __struct.coordinate_frame =
23824 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23825 enum_type: "MavFrame",
23826 value: tmp as u32,
23827 })?;
23828 Ok(__struct)
23829 }
23830 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23831 let mut __tmp = BytesMut::new(bytes);
23832 #[allow(clippy::absurd_extreme_comparisons)]
23833 #[allow(unused_comparisons)]
23834 if __tmp.remaining() < Self::ENCODED_LEN {
23835 panic!(
23836 "buffer is too small (need {} bytes, but got {})",
23837 Self::ENCODED_LEN,
23838 __tmp.remaining(),
23839 )
23840 }
23841 __tmp.put_u32_le(self.time_boot_ms);
23842 __tmp.put_f32_le(self.x);
23843 __tmp.put_f32_le(self.y);
23844 __tmp.put_f32_le(self.z);
23845 __tmp.put_f32_le(self.vx);
23846 __tmp.put_f32_le(self.vy);
23847 __tmp.put_f32_le(self.vz);
23848 __tmp.put_f32_le(self.afx);
23849 __tmp.put_f32_le(self.afy);
23850 __tmp.put_f32_le(self.afz);
23851 __tmp.put_f32_le(self.yaw);
23852 __tmp.put_f32_le(self.yaw_rate);
23853 __tmp.put_u16_le(self.type_mask.bits());
23854 __tmp.put_u8(self.coordinate_frame as u8);
23855 if matches!(version, MavlinkVersion::V2) {
23856 let len = __tmp.len();
23857 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23858 } else {
23859 __tmp.len()
23860 }
23861 }
23862}
23863#[doc = "id: 125"]
23864#[doc = "Power supply status."]
23865#[derive(Debug, Clone, PartialEq)]
23866#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23867#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23868pub struct POWER_STATUS_DATA {
23869 #[doc = "5V rail voltage."]
23870 pub Vcc: u16,
23871 #[doc = "Servo rail voltage."]
23872 pub Vservo: u16,
23873 #[doc = "Bitmap of power supply status flags."]
23874 pub flags: MavPowerStatus,
23875}
23876impl POWER_STATUS_DATA {
23877 pub const ENCODED_LEN: usize = 6usize;
23878 pub const DEFAULT: Self = Self {
23879 Vcc: 0_u16,
23880 Vservo: 0_u16,
23881 flags: MavPowerStatus::DEFAULT,
23882 };
23883 #[cfg(feature = "arbitrary")]
23884 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23885 use arbitrary::{Arbitrary, Unstructured};
23886 let mut buf = [0u8; 1024];
23887 rng.fill_bytes(&mut buf);
23888 let mut unstructured = Unstructured::new(&buf);
23889 Self::arbitrary(&mut unstructured).unwrap_or_default()
23890 }
23891}
23892impl Default for POWER_STATUS_DATA {
23893 fn default() -> Self {
23894 Self::DEFAULT.clone()
23895 }
23896}
23897impl MessageData for POWER_STATUS_DATA {
23898 type Message = MavMessage;
23899 const ID: u32 = 125u32;
23900 const NAME: &'static str = "POWER_STATUS";
23901 const EXTRA_CRC: u8 = 203u8;
23902 const ENCODED_LEN: usize = 6usize;
23903 fn deser(
23904 _version: MavlinkVersion,
23905 __input: &[u8],
23906 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23907 let avail_len = __input.len();
23908 let mut payload_buf = [0; Self::ENCODED_LEN];
23909 let mut buf = if avail_len < Self::ENCODED_LEN {
23910 payload_buf[0..avail_len].copy_from_slice(__input);
23911 Bytes::new(&payload_buf)
23912 } else {
23913 Bytes::new(__input)
23914 };
23915 let mut __struct = Self::default();
23916 __struct.Vcc = buf.get_u16_le();
23917 __struct.Vservo = buf.get_u16_le();
23918 let tmp = buf.get_u16_le();
23919 __struct.flags = MavPowerStatus::from_bits(tmp & MavPowerStatus::all().bits()).ok_or(
23920 ::mavlink_core::error::ParserError::InvalidFlag {
23921 flag_type: "MavPowerStatus",
23922 value: tmp as u32,
23923 },
23924 )?;
23925 Ok(__struct)
23926 }
23927 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23928 let mut __tmp = BytesMut::new(bytes);
23929 #[allow(clippy::absurd_extreme_comparisons)]
23930 #[allow(unused_comparisons)]
23931 if __tmp.remaining() < Self::ENCODED_LEN {
23932 panic!(
23933 "buffer is too small (need {} bytes, but got {})",
23934 Self::ENCODED_LEN,
23935 __tmp.remaining(),
23936 )
23937 }
23938 __tmp.put_u16_le(self.Vcc);
23939 __tmp.put_u16_le(self.Vservo);
23940 __tmp.put_u16_le(self.flags.bits());
23941 if matches!(version, MavlinkVersion::V2) {
23942 let len = __tmp.len();
23943 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23944 } else {
23945 __tmp.len()
23946 }
23947 }
23948}
23949#[doc = "id: 300"]
23950#[doc = "Version and capability of protocol version. This message can be requested with MAV_CMD_REQUEST_MESSAGE and is used as part of the handshaking to establish which MAVLink version should be used on the network. Every node should respond to a request for PROTOCOL_VERSION to enable the handshaking. Library implementers should consider adding this into the default decoding state machine to allow the protocol core to respond directly."]
23951#[derive(Debug, Clone, PartialEq)]
23952#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23953#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23954pub struct PROTOCOL_VERSION_DATA {
23955 #[doc = "Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc."]
23956 pub version: u16,
23957 #[doc = "Minimum MAVLink version supported"]
23958 pub min_version: u16,
23959 #[doc = "Maximum MAVLink version supported (set to the same value as version by default)"]
23960 pub max_version: u16,
23961 #[doc = "The first 8 bytes (not characters printed in hex!) of the git hash."]
23962 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23963 pub spec_version_hash: [u8; 8],
23964 #[doc = "The first 8 bytes (not characters printed in hex!) of the git hash."]
23965 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23966 pub library_version_hash: [u8; 8],
23967}
23968impl PROTOCOL_VERSION_DATA {
23969 pub const ENCODED_LEN: usize = 22usize;
23970 pub const DEFAULT: Self = Self {
23971 version: 0_u16,
23972 min_version: 0_u16,
23973 max_version: 0_u16,
23974 spec_version_hash: [0_u8; 8usize],
23975 library_version_hash: [0_u8; 8usize],
23976 };
23977 #[cfg(feature = "arbitrary")]
23978 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23979 use arbitrary::{Arbitrary, Unstructured};
23980 let mut buf = [0u8; 1024];
23981 rng.fill_bytes(&mut buf);
23982 let mut unstructured = Unstructured::new(&buf);
23983 Self::arbitrary(&mut unstructured).unwrap_or_default()
23984 }
23985}
23986impl Default for PROTOCOL_VERSION_DATA {
23987 fn default() -> Self {
23988 Self::DEFAULT.clone()
23989 }
23990}
23991impl MessageData for PROTOCOL_VERSION_DATA {
23992 type Message = MavMessage;
23993 const ID: u32 = 300u32;
23994 const NAME: &'static str = "PROTOCOL_VERSION";
23995 const EXTRA_CRC: u8 = 217u8;
23996 const ENCODED_LEN: usize = 22usize;
23997 fn deser(
23998 _version: MavlinkVersion,
23999 __input: &[u8],
24000 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24001 let avail_len = __input.len();
24002 let mut payload_buf = [0; Self::ENCODED_LEN];
24003 let mut buf = if avail_len < Self::ENCODED_LEN {
24004 payload_buf[0..avail_len].copy_from_slice(__input);
24005 Bytes::new(&payload_buf)
24006 } else {
24007 Bytes::new(__input)
24008 };
24009 let mut __struct = Self::default();
24010 __struct.version = buf.get_u16_le();
24011 __struct.min_version = buf.get_u16_le();
24012 __struct.max_version = buf.get_u16_le();
24013 for v in &mut __struct.spec_version_hash {
24014 let val = buf.get_u8();
24015 *v = val;
24016 }
24017 for v in &mut __struct.library_version_hash {
24018 let val = buf.get_u8();
24019 *v = val;
24020 }
24021 Ok(__struct)
24022 }
24023 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24024 let mut __tmp = BytesMut::new(bytes);
24025 #[allow(clippy::absurd_extreme_comparisons)]
24026 #[allow(unused_comparisons)]
24027 if __tmp.remaining() < Self::ENCODED_LEN {
24028 panic!(
24029 "buffer is too small (need {} bytes, but got {})",
24030 Self::ENCODED_LEN,
24031 __tmp.remaining(),
24032 )
24033 }
24034 __tmp.put_u16_le(self.version);
24035 __tmp.put_u16_le(self.min_version);
24036 __tmp.put_u16_le(self.max_version);
24037 for val in &self.spec_version_hash {
24038 __tmp.put_u8(*val);
24039 }
24040 for val in &self.library_version_hash {
24041 __tmp.put_u8(*val);
24042 }
24043 if matches!(version, MavlinkVersion::V2) {
24044 let len = __tmp.len();
24045 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24046 } else {
24047 __tmp.len()
24048 }
24049 }
24050}
24051#[doc = "id: 109"]
24052#[doc = "Status generated by radio and injected into MAVLink stream."]
24053#[derive(Debug, Clone, PartialEq)]
24054#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24055#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24056pub struct RADIO_STATUS_DATA {
24057 #[doc = "Count of radio packet receive errors (since boot)."]
24058 pub rxerrors: u16,
24059 #[doc = "Count of error corrected radio packets (since boot)."]
24060 pub fixed: u16,
24061 #[doc = "Local (message sender) received signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
24062 pub rssi: u8,
24063 #[doc = "Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
24064 pub remrssi: u8,
24065 #[doc = "Remaining free transmitter buffer space."]
24066 pub txbuf: u8,
24067 #[doc = "Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown."]
24068 pub noise: u8,
24069 #[doc = "Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown."]
24070 pub remnoise: u8,
24071}
24072impl RADIO_STATUS_DATA {
24073 pub const ENCODED_LEN: usize = 9usize;
24074 pub const DEFAULT: Self = Self {
24075 rxerrors: 0_u16,
24076 fixed: 0_u16,
24077 rssi: 0_u8,
24078 remrssi: 0_u8,
24079 txbuf: 0_u8,
24080 noise: 0_u8,
24081 remnoise: 0_u8,
24082 };
24083 #[cfg(feature = "arbitrary")]
24084 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24085 use arbitrary::{Arbitrary, Unstructured};
24086 let mut buf = [0u8; 1024];
24087 rng.fill_bytes(&mut buf);
24088 let mut unstructured = Unstructured::new(&buf);
24089 Self::arbitrary(&mut unstructured).unwrap_or_default()
24090 }
24091}
24092impl Default for RADIO_STATUS_DATA {
24093 fn default() -> Self {
24094 Self::DEFAULT.clone()
24095 }
24096}
24097impl MessageData for RADIO_STATUS_DATA {
24098 type Message = MavMessage;
24099 const ID: u32 = 109u32;
24100 const NAME: &'static str = "RADIO_STATUS";
24101 const EXTRA_CRC: u8 = 185u8;
24102 const ENCODED_LEN: usize = 9usize;
24103 fn deser(
24104 _version: MavlinkVersion,
24105 __input: &[u8],
24106 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24107 let avail_len = __input.len();
24108 let mut payload_buf = [0; Self::ENCODED_LEN];
24109 let mut buf = if avail_len < Self::ENCODED_LEN {
24110 payload_buf[0..avail_len].copy_from_slice(__input);
24111 Bytes::new(&payload_buf)
24112 } else {
24113 Bytes::new(__input)
24114 };
24115 let mut __struct = Self::default();
24116 __struct.rxerrors = buf.get_u16_le();
24117 __struct.fixed = buf.get_u16_le();
24118 __struct.rssi = buf.get_u8();
24119 __struct.remrssi = buf.get_u8();
24120 __struct.txbuf = buf.get_u8();
24121 __struct.noise = buf.get_u8();
24122 __struct.remnoise = buf.get_u8();
24123 Ok(__struct)
24124 }
24125 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24126 let mut __tmp = BytesMut::new(bytes);
24127 #[allow(clippy::absurd_extreme_comparisons)]
24128 #[allow(unused_comparisons)]
24129 if __tmp.remaining() < Self::ENCODED_LEN {
24130 panic!(
24131 "buffer is too small (need {} bytes, but got {})",
24132 Self::ENCODED_LEN,
24133 __tmp.remaining(),
24134 )
24135 }
24136 __tmp.put_u16_le(self.rxerrors);
24137 __tmp.put_u16_le(self.fixed);
24138 __tmp.put_u8(self.rssi);
24139 __tmp.put_u8(self.remrssi);
24140 __tmp.put_u8(self.txbuf);
24141 __tmp.put_u8(self.noise);
24142 __tmp.put_u8(self.remnoise);
24143 if matches!(version, MavlinkVersion::V2) {
24144 let len = __tmp.len();
24145 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24146 } else {
24147 __tmp.len()
24148 }
24149 }
24150}
24151#[doc = "id: 27"]
24152#[doc = "The RAW IMU readings for a 9DOF sensor, which is identified by the id (default IMU1). This message should always contain the true raw values without any scaling to allow data capture and system debugging."]
24153#[derive(Debug, Clone, PartialEq)]
24154#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24155#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24156pub struct RAW_IMU_DATA {
24157 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
24158 pub time_usec: u64,
24159 #[doc = "X acceleration (raw)"]
24160 pub xacc: i16,
24161 #[doc = "Y acceleration (raw)"]
24162 pub yacc: i16,
24163 #[doc = "Z acceleration (raw)"]
24164 pub zacc: i16,
24165 #[doc = "Angular speed around X axis (raw)"]
24166 pub xgyro: i16,
24167 #[doc = "Angular speed around Y axis (raw)"]
24168 pub ygyro: i16,
24169 #[doc = "Angular speed around Z axis (raw)"]
24170 pub zgyro: i16,
24171 #[doc = "X Magnetic field (raw)"]
24172 pub xmag: i16,
24173 #[doc = "Y Magnetic field (raw)"]
24174 pub ymag: i16,
24175 #[doc = "Z Magnetic field (raw)"]
24176 pub zmag: i16,
24177 #[doc = "Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)"]
24178 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24179 pub id: u8,
24180 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
24181 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24182 pub temperature: i16,
24183}
24184impl RAW_IMU_DATA {
24185 pub const ENCODED_LEN: usize = 29usize;
24186 pub const DEFAULT: Self = Self {
24187 time_usec: 0_u64,
24188 xacc: 0_i16,
24189 yacc: 0_i16,
24190 zacc: 0_i16,
24191 xgyro: 0_i16,
24192 ygyro: 0_i16,
24193 zgyro: 0_i16,
24194 xmag: 0_i16,
24195 ymag: 0_i16,
24196 zmag: 0_i16,
24197 id: 0_u8,
24198 temperature: 0_i16,
24199 };
24200 #[cfg(feature = "arbitrary")]
24201 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24202 use arbitrary::{Arbitrary, Unstructured};
24203 let mut buf = [0u8; 1024];
24204 rng.fill_bytes(&mut buf);
24205 let mut unstructured = Unstructured::new(&buf);
24206 Self::arbitrary(&mut unstructured).unwrap_or_default()
24207 }
24208}
24209impl Default for RAW_IMU_DATA {
24210 fn default() -> Self {
24211 Self::DEFAULT.clone()
24212 }
24213}
24214impl MessageData for RAW_IMU_DATA {
24215 type Message = MavMessage;
24216 const ID: u32 = 27u32;
24217 const NAME: &'static str = "RAW_IMU";
24218 const EXTRA_CRC: u8 = 144u8;
24219 const ENCODED_LEN: usize = 29usize;
24220 fn deser(
24221 _version: MavlinkVersion,
24222 __input: &[u8],
24223 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24224 let avail_len = __input.len();
24225 let mut payload_buf = [0; Self::ENCODED_LEN];
24226 let mut buf = if avail_len < Self::ENCODED_LEN {
24227 payload_buf[0..avail_len].copy_from_slice(__input);
24228 Bytes::new(&payload_buf)
24229 } else {
24230 Bytes::new(__input)
24231 };
24232 let mut __struct = Self::default();
24233 __struct.time_usec = buf.get_u64_le();
24234 __struct.xacc = buf.get_i16_le();
24235 __struct.yacc = buf.get_i16_le();
24236 __struct.zacc = buf.get_i16_le();
24237 __struct.xgyro = buf.get_i16_le();
24238 __struct.ygyro = buf.get_i16_le();
24239 __struct.zgyro = buf.get_i16_le();
24240 __struct.xmag = buf.get_i16_le();
24241 __struct.ymag = buf.get_i16_le();
24242 __struct.zmag = buf.get_i16_le();
24243 __struct.id = buf.get_u8();
24244 __struct.temperature = buf.get_i16_le();
24245 Ok(__struct)
24246 }
24247 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24248 let mut __tmp = BytesMut::new(bytes);
24249 #[allow(clippy::absurd_extreme_comparisons)]
24250 #[allow(unused_comparisons)]
24251 if __tmp.remaining() < Self::ENCODED_LEN {
24252 panic!(
24253 "buffer is too small (need {} bytes, but got {})",
24254 Self::ENCODED_LEN,
24255 __tmp.remaining(),
24256 )
24257 }
24258 __tmp.put_u64_le(self.time_usec);
24259 __tmp.put_i16_le(self.xacc);
24260 __tmp.put_i16_le(self.yacc);
24261 __tmp.put_i16_le(self.zacc);
24262 __tmp.put_i16_le(self.xgyro);
24263 __tmp.put_i16_le(self.ygyro);
24264 __tmp.put_i16_le(self.zgyro);
24265 __tmp.put_i16_le(self.xmag);
24266 __tmp.put_i16_le(self.ymag);
24267 __tmp.put_i16_le(self.zmag);
24268 __tmp.put_u8(self.id);
24269 __tmp.put_i16_le(self.temperature);
24270 if matches!(version, MavlinkVersion::V2) {
24271 let len = __tmp.len();
24272 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24273 } else {
24274 __tmp.len()
24275 }
24276 }
24277}
24278#[doc = "id: 28"]
24279#[doc = "The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values."]
24280#[derive(Debug, Clone, PartialEq)]
24281#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24282#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24283pub struct RAW_PRESSURE_DATA {
24284 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
24285 pub time_usec: u64,
24286 #[doc = "Absolute pressure (raw)"]
24287 pub press_abs: i16,
24288 #[doc = "Differential pressure 1 (raw, 0 if nonexistent)"]
24289 pub press_diff1: i16,
24290 #[doc = "Differential pressure 2 (raw, 0 if nonexistent)"]
24291 pub press_diff2: i16,
24292 #[doc = "Raw Temperature measurement (raw)"]
24293 pub temperature: i16,
24294}
24295impl RAW_PRESSURE_DATA {
24296 pub const ENCODED_LEN: usize = 16usize;
24297 pub const DEFAULT: Self = Self {
24298 time_usec: 0_u64,
24299 press_abs: 0_i16,
24300 press_diff1: 0_i16,
24301 press_diff2: 0_i16,
24302 temperature: 0_i16,
24303 };
24304 #[cfg(feature = "arbitrary")]
24305 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24306 use arbitrary::{Arbitrary, Unstructured};
24307 let mut buf = [0u8; 1024];
24308 rng.fill_bytes(&mut buf);
24309 let mut unstructured = Unstructured::new(&buf);
24310 Self::arbitrary(&mut unstructured).unwrap_or_default()
24311 }
24312}
24313impl Default for RAW_PRESSURE_DATA {
24314 fn default() -> Self {
24315 Self::DEFAULT.clone()
24316 }
24317}
24318impl MessageData for RAW_PRESSURE_DATA {
24319 type Message = MavMessage;
24320 const ID: u32 = 28u32;
24321 const NAME: &'static str = "RAW_PRESSURE";
24322 const EXTRA_CRC: u8 = 67u8;
24323 const ENCODED_LEN: usize = 16usize;
24324 fn deser(
24325 _version: MavlinkVersion,
24326 __input: &[u8],
24327 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24328 let avail_len = __input.len();
24329 let mut payload_buf = [0; Self::ENCODED_LEN];
24330 let mut buf = if avail_len < Self::ENCODED_LEN {
24331 payload_buf[0..avail_len].copy_from_slice(__input);
24332 Bytes::new(&payload_buf)
24333 } else {
24334 Bytes::new(__input)
24335 };
24336 let mut __struct = Self::default();
24337 __struct.time_usec = buf.get_u64_le();
24338 __struct.press_abs = buf.get_i16_le();
24339 __struct.press_diff1 = buf.get_i16_le();
24340 __struct.press_diff2 = buf.get_i16_le();
24341 __struct.temperature = buf.get_i16_le();
24342 Ok(__struct)
24343 }
24344 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24345 let mut __tmp = BytesMut::new(bytes);
24346 #[allow(clippy::absurd_extreme_comparisons)]
24347 #[allow(unused_comparisons)]
24348 if __tmp.remaining() < Self::ENCODED_LEN {
24349 panic!(
24350 "buffer is too small (need {} bytes, but got {})",
24351 Self::ENCODED_LEN,
24352 __tmp.remaining(),
24353 )
24354 }
24355 __tmp.put_u64_le(self.time_usec);
24356 __tmp.put_i16_le(self.press_abs);
24357 __tmp.put_i16_le(self.press_diff1);
24358 __tmp.put_i16_le(self.press_diff2);
24359 __tmp.put_i16_le(self.temperature);
24360 if matches!(version, MavlinkVersion::V2) {
24361 let len = __tmp.len();
24362 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24363 } else {
24364 __tmp.len()
24365 }
24366 }
24367}
24368#[doc = "id: 339"]
24369#[doc = "RPM sensor data message."]
24370#[derive(Debug, Clone, PartialEq)]
24371#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24372#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24373pub struct RAW_RPM_DATA {
24374 #[doc = "Indicated rate"]
24375 pub frequency: f32,
24376 #[doc = "Index of this RPM sensor (0-indexed)"]
24377 pub index: u8,
24378}
24379impl RAW_RPM_DATA {
24380 pub const ENCODED_LEN: usize = 5usize;
24381 pub const DEFAULT: Self = Self {
24382 frequency: 0.0_f32,
24383 index: 0_u8,
24384 };
24385 #[cfg(feature = "arbitrary")]
24386 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24387 use arbitrary::{Arbitrary, Unstructured};
24388 let mut buf = [0u8; 1024];
24389 rng.fill_bytes(&mut buf);
24390 let mut unstructured = Unstructured::new(&buf);
24391 Self::arbitrary(&mut unstructured).unwrap_or_default()
24392 }
24393}
24394impl Default for RAW_RPM_DATA {
24395 fn default() -> Self {
24396 Self::DEFAULT.clone()
24397 }
24398}
24399impl MessageData for RAW_RPM_DATA {
24400 type Message = MavMessage;
24401 const ID: u32 = 339u32;
24402 const NAME: &'static str = "RAW_RPM";
24403 const EXTRA_CRC: u8 = 199u8;
24404 const ENCODED_LEN: usize = 5usize;
24405 fn deser(
24406 _version: MavlinkVersion,
24407 __input: &[u8],
24408 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24409 let avail_len = __input.len();
24410 let mut payload_buf = [0; Self::ENCODED_LEN];
24411 let mut buf = if avail_len < Self::ENCODED_LEN {
24412 payload_buf[0..avail_len].copy_from_slice(__input);
24413 Bytes::new(&payload_buf)
24414 } else {
24415 Bytes::new(__input)
24416 };
24417 let mut __struct = Self::default();
24418 __struct.frequency = buf.get_f32_le();
24419 __struct.index = buf.get_u8();
24420 Ok(__struct)
24421 }
24422 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24423 let mut __tmp = BytesMut::new(bytes);
24424 #[allow(clippy::absurd_extreme_comparisons)]
24425 #[allow(unused_comparisons)]
24426 if __tmp.remaining() < Self::ENCODED_LEN {
24427 panic!(
24428 "buffer is too small (need {} bytes, but got {})",
24429 Self::ENCODED_LEN,
24430 __tmp.remaining(),
24431 )
24432 }
24433 __tmp.put_f32_le(self.frequency);
24434 __tmp.put_u8(self.index);
24435 if matches!(version, MavlinkVersion::V2) {
24436 let len = __tmp.len();
24437 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24438 } else {
24439 __tmp.len()
24440 }
24441 }
24442}
24443#[doc = "id: 65"]
24444#[doc = "The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification."]
24445#[derive(Debug, Clone, PartialEq)]
24446#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24447#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24448pub struct RC_CHANNELS_DATA {
24449 #[doc = "Timestamp (time since system boot)."]
24450 pub time_boot_ms: u32,
24451 #[doc = "RC channel 1 value."]
24452 pub chan1_raw: u16,
24453 #[doc = "RC channel 2 value."]
24454 pub chan2_raw: u16,
24455 #[doc = "RC channel 3 value."]
24456 pub chan3_raw: u16,
24457 #[doc = "RC channel 4 value."]
24458 pub chan4_raw: u16,
24459 #[doc = "RC channel 5 value."]
24460 pub chan5_raw: u16,
24461 #[doc = "RC channel 6 value."]
24462 pub chan6_raw: u16,
24463 #[doc = "RC channel 7 value."]
24464 pub chan7_raw: u16,
24465 #[doc = "RC channel 8 value."]
24466 pub chan8_raw: u16,
24467 #[doc = "RC channel 9 value."]
24468 pub chan9_raw: u16,
24469 #[doc = "RC channel 10 value."]
24470 pub chan10_raw: u16,
24471 #[doc = "RC channel 11 value."]
24472 pub chan11_raw: u16,
24473 #[doc = "RC channel 12 value."]
24474 pub chan12_raw: u16,
24475 #[doc = "RC channel 13 value."]
24476 pub chan13_raw: u16,
24477 #[doc = "RC channel 14 value."]
24478 pub chan14_raw: u16,
24479 #[doc = "RC channel 15 value."]
24480 pub chan15_raw: u16,
24481 #[doc = "RC channel 16 value."]
24482 pub chan16_raw: u16,
24483 #[doc = "RC channel 17 value."]
24484 pub chan17_raw: u16,
24485 #[doc = "RC channel 18 value."]
24486 pub chan18_raw: u16,
24487 #[doc = "Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available."]
24488 pub chancount: u8,
24489 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
24490 pub rssi: u8,
24491}
24492impl RC_CHANNELS_DATA {
24493 pub const ENCODED_LEN: usize = 42usize;
24494 pub const DEFAULT: Self = Self {
24495 time_boot_ms: 0_u32,
24496 chan1_raw: 0_u16,
24497 chan2_raw: 0_u16,
24498 chan3_raw: 0_u16,
24499 chan4_raw: 0_u16,
24500 chan5_raw: 0_u16,
24501 chan6_raw: 0_u16,
24502 chan7_raw: 0_u16,
24503 chan8_raw: 0_u16,
24504 chan9_raw: 0_u16,
24505 chan10_raw: 0_u16,
24506 chan11_raw: 0_u16,
24507 chan12_raw: 0_u16,
24508 chan13_raw: 0_u16,
24509 chan14_raw: 0_u16,
24510 chan15_raw: 0_u16,
24511 chan16_raw: 0_u16,
24512 chan17_raw: 0_u16,
24513 chan18_raw: 0_u16,
24514 chancount: 0_u8,
24515 rssi: 0_u8,
24516 };
24517 #[cfg(feature = "arbitrary")]
24518 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24519 use arbitrary::{Arbitrary, Unstructured};
24520 let mut buf = [0u8; 1024];
24521 rng.fill_bytes(&mut buf);
24522 let mut unstructured = Unstructured::new(&buf);
24523 Self::arbitrary(&mut unstructured).unwrap_or_default()
24524 }
24525}
24526impl Default for RC_CHANNELS_DATA {
24527 fn default() -> Self {
24528 Self::DEFAULT.clone()
24529 }
24530}
24531impl MessageData for RC_CHANNELS_DATA {
24532 type Message = MavMessage;
24533 const ID: u32 = 65u32;
24534 const NAME: &'static str = "RC_CHANNELS";
24535 const EXTRA_CRC: u8 = 118u8;
24536 const ENCODED_LEN: usize = 42usize;
24537 fn deser(
24538 _version: MavlinkVersion,
24539 __input: &[u8],
24540 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24541 let avail_len = __input.len();
24542 let mut payload_buf = [0; Self::ENCODED_LEN];
24543 let mut buf = if avail_len < Self::ENCODED_LEN {
24544 payload_buf[0..avail_len].copy_from_slice(__input);
24545 Bytes::new(&payload_buf)
24546 } else {
24547 Bytes::new(__input)
24548 };
24549 let mut __struct = Self::default();
24550 __struct.time_boot_ms = buf.get_u32_le();
24551 __struct.chan1_raw = buf.get_u16_le();
24552 __struct.chan2_raw = buf.get_u16_le();
24553 __struct.chan3_raw = buf.get_u16_le();
24554 __struct.chan4_raw = buf.get_u16_le();
24555 __struct.chan5_raw = buf.get_u16_le();
24556 __struct.chan6_raw = buf.get_u16_le();
24557 __struct.chan7_raw = buf.get_u16_le();
24558 __struct.chan8_raw = buf.get_u16_le();
24559 __struct.chan9_raw = buf.get_u16_le();
24560 __struct.chan10_raw = buf.get_u16_le();
24561 __struct.chan11_raw = buf.get_u16_le();
24562 __struct.chan12_raw = buf.get_u16_le();
24563 __struct.chan13_raw = buf.get_u16_le();
24564 __struct.chan14_raw = buf.get_u16_le();
24565 __struct.chan15_raw = buf.get_u16_le();
24566 __struct.chan16_raw = buf.get_u16_le();
24567 __struct.chan17_raw = buf.get_u16_le();
24568 __struct.chan18_raw = buf.get_u16_le();
24569 __struct.chancount = buf.get_u8();
24570 __struct.rssi = buf.get_u8();
24571 Ok(__struct)
24572 }
24573 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24574 let mut __tmp = BytesMut::new(bytes);
24575 #[allow(clippy::absurd_extreme_comparisons)]
24576 #[allow(unused_comparisons)]
24577 if __tmp.remaining() < Self::ENCODED_LEN {
24578 panic!(
24579 "buffer is too small (need {} bytes, but got {})",
24580 Self::ENCODED_LEN,
24581 __tmp.remaining(),
24582 )
24583 }
24584 __tmp.put_u32_le(self.time_boot_ms);
24585 __tmp.put_u16_le(self.chan1_raw);
24586 __tmp.put_u16_le(self.chan2_raw);
24587 __tmp.put_u16_le(self.chan3_raw);
24588 __tmp.put_u16_le(self.chan4_raw);
24589 __tmp.put_u16_le(self.chan5_raw);
24590 __tmp.put_u16_le(self.chan6_raw);
24591 __tmp.put_u16_le(self.chan7_raw);
24592 __tmp.put_u16_le(self.chan8_raw);
24593 __tmp.put_u16_le(self.chan9_raw);
24594 __tmp.put_u16_le(self.chan10_raw);
24595 __tmp.put_u16_le(self.chan11_raw);
24596 __tmp.put_u16_le(self.chan12_raw);
24597 __tmp.put_u16_le(self.chan13_raw);
24598 __tmp.put_u16_le(self.chan14_raw);
24599 __tmp.put_u16_le(self.chan15_raw);
24600 __tmp.put_u16_le(self.chan16_raw);
24601 __tmp.put_u16_le(self.chan17_raw);
24602 __tmp.put_u16_le(self.chan18_raw);
24603 __tmp.put_u8(self.chancount);
24604 __tmp.put_u8(self.rssi);
24605 if matches!(version, MavlinkVersion::V2) {
24606 let len = __tmp.len();
24607 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24608 } else {
24609 __tmp.len()
24610 }
24611 }
24612}
24613#[doc = "id: 70"]
24614#[doc = "The RAW values of the RC channels sent to the MAV to override info received from the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. Note carefully the semantic differences between the first 8 channels and the subsequent channels."]
24615#[derive(Debug, Clone, PartialEq)]
24616#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24617#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24618pub struct RC_CHANNELS_OVERRIDE_DATA {
24619 #[doc = "RC channel 1 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
24620 pub chan1_raw: u16,
24621 #[doc = "RC channel 2 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
24622 pub chan2_raw: u16,
24623 #[doc = "RC channel 3 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
24624 pub chan3_raw: u16,
24625 #[doc = "RC channel 4 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
24626 pub chan4_raw: u16,
24627 #[doc = "RC channel 5 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
24628 pub chan5_raw: u16,
24629 #[doc = "RC channel 6 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
24630 pub chan6_raw: u16,
24631 #[doc = "RC channel 7 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
24632 pub chan7_raw: u16,
24633 #[doc = "RC channel 8 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
24634 pub chan8_raw: u16,
24635 #[doc = "System ID"]
24636 pub target_system: u8,
24637 #[doc = "Component ID"]
24638 pub target_component: u8,
24639 #[doc = "RC channel 9 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
24640 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24641 pub chan9_raw: u16,
24642 #[doc = "RC channel 10 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
24643 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24644 pub chan10_raw: u16,
24645 #[doc = "RC channel 11 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
24646 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24647 pub chan11_raw: u16,
24648 #[doc = "RC channel 12 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
24649 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24650 pub chan12_raw: u16,
24651 #[doc = "RC channel 13 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
24652 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24653 pub chan13_raw: u16,
24654 #[doc = "RC channel 14 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
24655 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24656 pub chan14_raw: u16,
24657 #[doc = "RC channel 15 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
24658 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24659 pub chan15_raw: u16,
24660 #[doc = "RC channel 16 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
24661 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24662 pub chan16_raw: u16,
24663 #[doc = "RC channel 17 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
24664 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24665 pub chan17_raw: u16,
24666 #[doc = "RC channel 18 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
24667 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24668 pub chan18_raw: u16,
24669}
24670impl RC_CHANNELS_OVERRIDE_DATA {
24671 pub const ENCODED_LEN: usize = 38usize;
24672 pub const DEFAULT: Self = Self {
24673 chan1_raw: 0_u16,
24674 chan2_raw: 0_u16,
24675 chan3_raw: 0_u16,
24676 chan4_raw: 0_u16,
24677 chan5_raw: 0_u16,
24678 chan6_raw: 0_u16,
24679 chan7_raw: 0_u16,
24680 chan8_raw: 0_u16,
24681 target_system: 0_u8,
24682 target_component: 0_u8,
24683 chan9_raw: 0_u16,
24684 chan10_raw: 0_u16,
24685 chan11_raw: 0_u16,
24686 chan12_raw: 0_u16,
24687 chan13_raw: 0_u16,
24688 chan14_raw: 0_u16,
24689 chan15_raw: 0_u16,
24690 chan16_raw: 0_u16,
24691 chan17_raw: 0_u16,
24692 chan18_raw: 0_u16,
24693 };
24694 #[cfg(feature = "arbitrary")]
24695 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24696 use arbitrary::{Arbitrary, Unstructured};
24697 let mut buf = [0u8; 1024];
24698 rng.fill_bytes(&mut buf);
24699 let mut unstructured = Unstructured::new(&buf);
24700 Self::arbitrary(&mut unstructured).unwrap_or_default()
24701 }
24702}
24703impl Default for RC_CHANNELS_OVERRIDE_DATA {
24704 fn default() -> Self {
24705 Self::DEFAULT.clone()
24706 }
24707}
24708impl MessageData for RC_CHANNELS_OVERRIDE_DATA {
24709 type Message = MavMessage;
24710 const ID: u32 = 70u32;
24711 const NAME: &'static str = "RC_CHANNELS_OVERRIDE";
24712 const EXTRA_CRC: u8 = 124u8;
24713 const ENCODED_LEN: usize = 38usize;
24714 fn deser(
24715 _version: MavlinkVersion,
24716 __input: &[u8],
24717 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24718 let avail_len = __input.len();
24719 let mut payload_buf = [0; Self::ENCODED_LEN];
24720 let mut buf = if avail_len < Self::ENCODED_LEN {
24721 payload_buf[0..avail_len].copy_from_slice(__input);
24722 Bytes::new(&payload_buf)
24723 } else {
24724 Bytes::new(__input)
24725 };
24726 let mut __struct = Self::default();
24727 __struct.chan1_raw = buf.get_u16_le();
24728 __struct.chan2_raw = buf.get_u16_le();
24729 __struct.chan3_raw = buf.get_u16_le();
24730 __struct.chan4_raw = buf.get_u16_le();
24731 __struct.chan5_raw = buf.get_u16_le();
24732 __struct.chan6_raw = buf.get_u16_le();
24733 __struct.chan7_raw = buf.get_u16_le();
24734 __struct.chan8_raw = buf.get_u16_le();
24735 __struct.target_system = buf.get_u8();
24736 __struct.target_component = buf.get_u8();
24737 __struct.chan9_raw = buf.get_u16_le();
24738 __struct.chan10_raw = buf.get_u16_le();
24739 __struct.chan11_raw = buf.get_u16_le();
24740 __struct.chan12_raw = buf.get_u16_le();
24741 __struct.chan13_raw = buf.get_u16_le();
24742 __struct.chan14_raw = buf.get_u16_le();
24743 __struct.chan15_raw = buf.get_u16_le();
24744 __struct.chan16_raw = buf.get_u16_le();
24745 __struct.chan17_raw = buf.get_u16_le();
24746 __struct.chan18_raw = buf.get_u16_le();
24747 Ok(__struct)
24748 }
24749 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24750 let mut __tmp = BytesMut::new(bytes);
24751 #[allow(clippy::absurd_extreme_comparisons)]
24752 #[allow(unused_comparisons)]
24753 if __tmp.remaining() < Self::ENCODED_LEN {
24754 panic!(
24755 "buffer is too small (need {} bytes, but got {})",
24756 Self::ENCODED_LEN,
24757 __tmp.remaining(),
24758 )
24759 }
24760 __tmp.put_u16_le(self.chan1_raw);
24761 __tmp.put_u16_le(self.chan2_raw);
24762 __tmp.put_u16_le(self.chan3_raw);
24763 __tmp.put_u16_le(self.chan4_raw);
24764 __tmp.put_u16_le(self.chan5_raw);
24765 __tmp.put_u16_le(self.chan6_raw);
24766 __tmp.put_u16_le(self.chan7_raw);
24767 __tmp.put_u16_le(self.chan8_raw);
24768 __tmp.put_u8(self.target_system);
24769 __tmp.put_u8(self.target_component);
24770 __tmp.put_u16_le(self.chan9_raw);
24771 __tmp.put_u16_le(self.chan10_raw);
24772 __tmp.put_u16_le(self.chan11_raw);
24773 __tmp.put_u16_le(self.chan12_raw);
24774 __tmp.put_u16_le(self.chan13_raw);
24775 __tmp.put_u16_le(self.chan14_raw);
24776 __tmp.put_u16_le(self.chan15_raw);
24777 __tmp.put_u16_le(self.chan16_raw);
24778 __tmp.put_u16_le(self.chan17_raw);
24779 __tmp.put_u16_le(self.chan18_raw);
24780 if matches!(version, MavlinkVersion::V2) {
24781 let len = __tmp.len();
24782 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24783 } else {
24784 __tmp.len()
24785 }
24786 }
24787}
24788#[doc = "id: 35"]
24789#[doc = "The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification."]
24790#[derive(Debug, Clone, PartialEq)]
24791#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24792#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24793pub struct RC_CHANNELS_RAW_DATA {
24794 #[doc = "Timestamp (time since system boot)."]
24795 pub time_boot_ms: u32,
24796 #[doc = "RC channel 1 value."]
24797 pub chan1_raw: u16,
24798 #[doc = "RC channel 2 value."]
24799 pub chan2_raw: u16,
24800 #[doc = "RC channel 3 value."]
24801 pub chan3_raw: u16,
24802 #[doc = "RC channel 4 value."]
24803 pub chan4_raw: u16,
24804 #[doc = "RC channel 5 value."]
24805 pub chan5_raw: u16,
24806 #[doc = "RC channel 6 value."]
24807 pub chan6_raw: u16,
24808 #[doc = "RC channel 7 value."]
24809 pub chan7_raw: u16,
24810 #[doc = "RC channel 8 value."]
24811 pub chan8_raw: u16,
24812 #[doc = "Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX."]
24813 pub port: u8,
24814 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
24815 pub rssi: u8,
24816}
24817impl RC_CHANNELS_RAW_DATA {
24818 pub const ENCODED_LEN: usize = 22usize;
24819 pub const DEFAULT: Self = Self {
24820 time_boot_ms: 0_u32,
24821 chan1_raw: 0_u16,
24822 chan2_raw: 0_u16,
24823 chan3_raw: 0_u16,
24824 chan4_raw: 0_u16,
24825 chan5_raw: 0_u16,
24826 chan6_raw: 0_u16,
24827 chan7_raw: 0_u16,
24828 chan8_raw: 0_u16,
24829 port: 0_u8,
24830 rssi: 0_u8,
24831 };
24832 #[cfg(feature = "arbitrary")]
24833 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24834 use arbitrary::{Arbitrary, Unstructured};
24835 let mut buf = [0u8; 1024];
24836 rng.fill_bytes(&mut buf);
24837 let mut unstructured = Unstructured::new(&buf);
24838 Self::arbitrary(&mut unstructured).unwrap_or_default()
24839 }
24840}
24841impl Default for RC_CHANNELS_RAW_DATA {
24842 fn default() -> Self {
24843 Self::DEFAULT.clone()
24844 }
24845}
24846impl MessageData for RC_CHANNELS_RAW_DATA {
24847 type Message = MavMessage;
24848 const ID: u32 = 35u32;
24849 const NAME: &'static str = "RC_CHANNELS_RAW";
24850 const EXTRA_CRC: u8 = 244u8;
24851 const ENCODED_LEN: usize = 22usize;
24852 fn deser(
24853 _version: MavlinkVersion,
24854 __input: &[u8],
24855 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24856 let avail_len = __input.len();
24857 let mut payload_buf = [0; Self::ENCODED_LEN];
24858 let mut buf = if avail_len < Self::ENCODED_LEN {
24859 payload_buf[0..avail_len].copy_from_slice(__input);
24860 Bytes::new(&payload_buf)
24861 } else {
24862 Bytes::new(__input)
24863 };
24864 let mut __struct = Self::default();
24865 __struct.time_boot_ms = buf.get_u32_le();
24866 __struct.chan1_raw = buf.get_u16_le();
24867 __struct.chan2_raw = buf.get_u16_le();
24868 __struct.chan3_raw = buf.get_u16_le();
24869 __struct.chan4_raw = buf.get_u16_le();
24870 __struct.chan5_raw = buf.get_u16_le();
24871 __struct.chan6_raw = buf.get_u16_le();
24872 __struct.chan7_raw = buf.get_u16_le();
24873 __struct.chan8_raw = buf.get_u16_le();
24874 __struct.port = buf.get_u8();
24875 __struct.rssi = buf.get_u8();
24876 Ok(__struct)
24877 }
24878 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24879 let mut __tmp = BytesMut::new(bytes);
24880 #[allow(clippy::absurd_extreme_comparisons)]
24881 #[allow(unused_comparisons)]
24882 if __tmp.remaining() < Self::ENCODED_LEN {
24883 panic!(
24884 "buffer is too small (need {} bytes, but got {})",
24885 Self::ENCODED_LEN,
24886 __tmp.remaining(),
24887 )
24888 }
24889 __tmp.put_u32_le(self.time_boot_ms);
24890 __tmp.put_u16_le(self.chan1_raw);
24891 __tmp.put_u16_le(self.chan2_raw);
24892 __tmp.put_u16_le(self.chan3_raw);
24893 __tmp.put_u16_le(self.chan4_raw);
24894 __tmp.put_u16_le(self.chan5_raw);
24895 __tmp.put_u16_le(self.chan6_raw);
24896 __tmp.put_u16_le(self.chan7_raw);
24897 __tmp.put_u16_le(self.chan8_raw);
24898 __tmp.put_u8(self.port);
24899 __tmp.put_u8(self.rssi);
24900 if matches!(version, MavlinkVersion::V2) {
24901 let len = __tmp.len();
24902 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24903 } else {
24904 __tmp.len()
24905 }
24906 }
24907}
24908#[doc = "id: 34"]
24909#[doc = "The scaled values of the RC channels received: (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to INT16_MAX."]
24910#[derive(Debug, Clone, PartialEq)]
24911#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24912#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24913pub struct RC_CHANNELS_SCALED_DATA {
24914 #[doc = "Timestamp (time since system boot)."]
24915 pub time_boot_ms: u32,
24916 #[doc = "RC channel 1 value scaled."]
24917 pub chan1_scaled: i16,
24918 #[doc = "RC channel 2 value scaled."]
24919 pub chan2_scaled: i16,
24920 #[doc = "RC channel 3 value scaled."]
24921 pub chan3_scaled: i16,
24922 #[doc = "RC channel 4 value scaled."]
24923 pub chan4_scaled: i16,
24924 #[doc = "RC channel 5 value scaled."]
24925 pub chan5_scaled: i16,
24926 #[doc = "RC channel 6 value scaled."]
24927 pub chan6_scaled: i16,
24928 #[doc = "RC channel 7 value scaled."]
24929 pub chan7_scaled: i16,
24930 #[doc = "RC channel 8 value scaled."]
24931 pub chan8_scaled: i16,
24932 #[doc = "Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX."]
24933 pub port: u8,
24934 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
24935 pub rssi: u8,
24936}
24937impl RC_CHANNELS_SCALED_DATA {
24938 pub const ENCODED_LEN: usize = 22usize;
24939 pub const DEFAULT: Self = Self {
24940 time_boot_ms: 0_u32,
24941 chan1_scaled: 0_i16,
24942 chan2_scaled: 0_i16,
24943 chan3_scaled: 0_i16,
24944 chan4_scaled: 0_i16,
24945 chan5_scaled: 0_i16,
24946 chan6_scaled: 0_i16,
24947 chan7_scaled: 0_i16,
24948 chan8_scaled: 0_i16,
24949 port: 0_u8,
24950 rssi: 0_u8,
24951 };
24952 #[cfg(feature = "arbitrary")]
24953 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24954 use arbitrary::{Arbitrary, Unstructured};
24955 let mut buf = [0u8; 1024];
24956 rng.fill_bytes(&mut buf);
24957 let mut unstructured = Unstructured::new(&buf);
24958 Self::arbitrary(&mut unstructured).unwrap_or_default()
24959 }
24960}
24961impl Default for RC_CHANNELS_SCALED_DATA {
24962 fn default() -> Self {
24963 Self::DEFAULT.clone()
24964 }
24965}
24966impl MessageData for RC_CHANNELS_SCALED_DATA {
24967 type Message = MavMessage;
24968 const ID: u32 = 34u32;
24969 const NAME: &'static str = "RC_CHANNELS_SCALED";
24970 const EXTRA_CRC: u8 = 237u8;
24971 const ENCODED_LEN: usize = 22usize;
24972 fn deser(
24973 _version: MavlinkVersion,
24974 __input: &[u8],
24975 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24976 let avail_len = __input.len();
24977 let mut payload_buf = [0; Self::ENCODED_LEN];
24978 let mut buf = if avail_len < Self::ENCODED_LEN {
24979 payload_buf[0..avail_len].copy_from_slice(__input);
24980 Bytes::new(&payload_buf)
24981 } else {
24982 Bytes::new(__input)
24983 };
24984 let mut __struct = Self::default();
24985 __struct.time_boot_ms = buf.get_u32_le();
24986 __struct.chan1_scaled = buf.get_i16_le();
24987 __struct.chan2_scaled = buf.get_i16_le();
24988 __struct.chan3_scaled = buf.get_i16_le();
24989 __struct.chan4_scaled = buf.get_i16_le();
24990 __struct.chan5_scaled = buf.get_i16_le();
24991 __struct.chan6_scaled = buf.get_i16_le();
24992 __struct.chan7_scaled = buf.get_i16_le();
24993 __struct.chan8_scaled = buf.get_i16_le();
24994 __struct.port = buf.get_u8();
24995 __struct.rssi = buf.get_u8();
24996 Ok(__struct)
24997 }
24998 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24999 let mut __tmp = BytesMut::new(bytes);
25000 #[allow(clippy::absurd_extreme_comparisons)]
25001 #[allow(unused_comparisons)]
25002 if __tmp.remaining() < Self::ENCODED_LEN {
25003 panic!(
25004 "buffer is too small (need {} bytes, but got {})",
25005 Self::ENCODED_LEN,
25006 __tmp.remaining(),
25007 )
25008 }
25009 __tmp.put_u32_le(self.time_boot_ms);
25010 __tmp.put_i16_le(self.chan1_scaled);
25011 __tmp.put_i16_le(self.chan2_scaled);
25012 __tmp.put_i16_le(self.chan3_scaled);
25013 __tmp.put_i16_le(self.chan4_scaled);
25014 __tmp.put_i16_le(self.chan5_scaled);
25015 __tmp.put_i16_le(self.chan6_scaled);
25016 __tmp.put_i16_le(self.chan7_scaled);
25017 __tmp.put_i16_le(self.chan8_scaled);
25018 __tmp.put_u8(self.port);
25019 __tmp.put_u8(self.rssi);
25020 if matches!(version, MavlinkVersion::V2) {
25021 let len = __tmp.len();
25022 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25023 } else {
25024 __tmp.len()
25025 }
25026 }
25027}
25028#[doc = "id: 66"]
25029#[doc = "Request a data stream."]
25030#[derive(Debug, Clone, PartialEq)]
25031#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25032#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25033pub struct REQUEST_DATA_STREAM_DATA {
25034 #[doc = "The requested message rate"]
25035 pub req_message_rate: u16,
25036 #[doc = "The target requested to send the message stream."]
25037 pub target_system: u8,
25038 #[doc = "The target requested to send the message stream."]
25039 pub target_component: u8,
25040 #[doc = "The ID of the requested data stream"]
25041 pub req_stream_id: u8,
25042 #[doc = "1 to start sending, 0 to stop sending."]
25043 pub start_stop: u8,
25044}
25045impl REQUEST_DATA_STREAM_DATA {
25046 pub const ENCODED_LEN: usize = 6usize;
25047 pub const DEFAULT: Self = Self {
25048 req_message_rate: 0_u16,
25049 target_system: 0_u8,
25050 target_component: 0_u8,
25051 req_stream_id: 0_u8,
25052 start_stop: 0_u8,
25053 };
25054 #[cfg(feature = "arbitrary")]
25055 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25056 use arbitrary::{Arbitrary, Unstructured};
25057 let mut buf = [0u8; 1024];
25058 rng.fill_bytes(&mut buf);
25059 let mut unstructured = Unstructured::new(&buf);
25060 Self::arbitrary(&mut unstructured).unwrap_or_default()
25061 }
25062}
25063impl Default for REQUEST_DATA_STREAM_DATA {
25064 fn default() -> Self {
25065 Self::DEFAULT.clone()
25066 }
25067}
25068impl MessageData for REQUEST_DATA_STREAM_DATA {
25069 type Message = MavMessage;
25070 const ID: u32 = 66u32;
25071 const NAME: &'static str = "REQUEST_DATA_STREAM";
25072 const EXTRA_CRC: u8 = 148u8;
25073 const ENCODED_LEN: usize = 6usize;
25074 fn deser(
25075 _version: MavlinkVersion,
25076 __input: &[u8],
25077 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25078 let avail_len = __input.len();
25079 let mut payload_buf = [0; Self::ENCODED_LEN];
25080 let mut buf = if avail_len < Self::ENCODED_LEN {
25081 payload_buf[0..avail_len].copy_from_slice(__input);
25082 Bytes::new(&payload_buf)
25083 } else {
25084 Bytes::new(__input)
25085 };
25086 let mut __struct = Self::default();
25087 __struct.req_message_rate = buf.get_u16_le();
25088 __struct.target_system = buf.get_u8();
25089 __struct.target_component = buf.get_u8();
25090 __struct.req_stream_id = buf.get_u8();
25091 __struct.start_stop = buf.get_u8();
25092 Ok(__struct)
25093 }
25094 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25095 let mut __tmp = BytesMut::new(bytes);
25096 #[allow(clippy::absurd_extreme_comparisons)]
25097 #[allow(unused_comparisons)]
25098 if __tmp.remaining() < Self::ENCODED_LEN {
25099 panic!(
25100 "buffer is too small (need {} bytes, but got {})",
25101 Self::ENCODED_LEN,
25102 __tmp.remaining(),
25103 )
25104 }
25105 __tmp.put_u16_le(self.req_message_rate);
25106 __tmp.put_u8(self.target_system);
25107 __tmp.put_u8(self.target_component);
25108 __tmp.put_u8(self.req_stream_id);
25109 __tmp.put_u8(self.start_stop);
25110 if matches!(version, MavlinkVersion::V2) {
25111 let len = __tmp.len();
25112 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25113 } else {
25114 __tmp.len()
25115 }
25116 }
25117}
25118#[doc = "id: 412"]
25119#[doc = "Request one or more events to be (re-)sent. If first_sequence==last_sequence, only a single event is requested. Note that first_sequence can be larger than last_sequence (because the sequence number can wrap). Each sequence will trigger an EVENT or EVENT_ERROR response."]
25120#[derive(Debug, Clone, PartialEq)]
25121#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25122#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25123pub struct REQUEST_EVENT_DATA {
25124 #[doc = "First sequence number of the requested event."]
25125 pub first_sequence: u16,
25126 #[doc = "Last sequence number of the requested event."]
25127 pub last_sequence: u16,
25128 #[doc = "System ID"]
25129 pub target_system: u8,
25130 #[doc = "Component ID"]
25131 pub target_component: u8,
25132}
25133impl REQUEST_EVENT_DATA {
25134 pub const ENCODED_LEN: usize = 6usize;
25135 pub const DEFAULT: Self = Self {
25136 first_sequence: 0_u16,
25137 last_sequence: 0_u16,
25138 target_system: 0_u8,
25139 target_component: 0_u8,
25140 };
25141 #[cfg(feature = "arbitrary")]
25142 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25143 use arbitrary::{Arbitrary, Unstructured};
25144 let mut buf = [0u8; 1024];
25145 rng.fill_bytes(&mut buf);
25146 let mut unstructured = Unstructured::new(&buf);
25147 Self::arbitrary(&mut unstructured).unwrap_or_default()
25148 }
25149}
25150impl Default for REQUEST_EVENT_DATA {
25151 fn default() -> Self {
25152 Self::DEFAULT.clone()
25153 }
25154}
25155impl MessageData for REQUEST_EVENT_DATA {
25156 type Message = MavMessage;
25157 const ID: u32 = 412u32;
25158 const NAME: &'static str = "REQUEST_EVENT";
25159 const EXTRA_CRC: u8 = 33u8;
25160 const ENCODED_LEN: usize = 6usize;
25161 fn deser(
25162 _version: MavlinkVersion,
25163 __input: &[u8],
25164 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25165 let avail_len = __input.len();
25166 let mut payload_buf = [0; Self::ENCODED_LEN];
25167 let mut buf = if avail_len < Self::ENCODED_LEN {
25168 payload_buf[0..avail_len].copy_from_slice(__input);
25169 Bytes::new(&payload_buf)
25170 } else {
25171 Bytes::new(__input)
25172 };
25173 let mut __struct = Self::default();
25174 __struct.first_sequence = buf.get_u16_le();
25175 __struct.last_sequence = buf.get_u16_le();
25176 __struct.target_system = buf.get_u8();
25177 __struct.target_component = buf.get_u8();
25178 Ok(__struct)
25179 }
25180 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25181 let mut __tmp = BytesMut::new(bytes);
25182 #[allow(clippy::absurd_extreme_comparisons)]
25183 #[allow(unused_comparisons)]
25184 if __tmp.remaining() < Self::ENCODED_LEN {
25185 panic!(
25186 "buffer is too small (need {} bytes, but got {})",
25187 Self::ENCODED_LEN,
25188 __tmp.remaining(),
25189 )
25190 }
25191 __tmp.put_u16_le(self.first_sequence);
25192 __tmp.put_u16_le(self.last_sequence);
25193 __tmp.put_u8(self.target_system);
25194 __tmp.put_u8(self.target_component);
25195 if matches!(version, MavlinkVersion::V2) {
25196 let len = __tmp.len();
25197 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25198 } else {
25199 __tmp.len()
25200 }
25201 }
25202}
25203#[doc = "id: 142"]
25204#[doc = "The autopilot is requesting a resource (file, binary, other type of data)."]
25205#[derive(Debug, Clone, PartialEq)]
25206#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25207#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25208pub struct RESOURCE_REQUEST_DATA {
25209 #[doc = "Request ID. This ID should be re-used when sending back URI contents"]
25210 pub request_id: u8,
25211 #[doc = "The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary"]
25212 pub uri_type: u8,
25213 #[doc = "The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum)"]
25214 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
25215 pub uri: [u8; 120],
25216 #[doc = "The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream."]
25217 pub transfer_type: u8,
25218 #[doc = "The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP)."]
25219 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
25220 pub storage: [u8; 120],
25221}
25222impl RESOURCE_REQUEST_DATA {
25223 pub const ENCODED_LEN: usize = 243usize;
25224 pub const DEFAULT: Self = Self {
25225 request_id: 0_u8,
25226 uri_type: 0_u8,
25227 uri: [0_u8; 120usize],
25228 transfer_type: 0_u8,
25229 storage: [0_u8; 120usize],
25230 };
25231 #[cfg(feature = "arbitrary")]
25232 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25233 use arbitrary::{Arbitrary, Unstructured};
25234 let mut buf = [0u8; 1024];
25235 rng.fill_bytes(&mut buf);
25236 let mut unstructured = Unstructured::new(&buf);
25237 Self::arbitrary(&mut unstructured).unwrap_or_default()
25238 }
25239}
25240impl Default for RESOURCE_REQUEST_DATA {
25241 fn default() -> Self {
25242 Self::DEFAULT.clone()
25243 }
25244}
25245impl MessageData for RESOURCE_REQUEST_DATA {
25246 type Message = MavMessage;
25247 const ID: u32 = 142u32;
25248 const NAME: &'static str = "RESOURCE_REQUEST";
25249 const EXTRA_CRC: u8 = 72u8;
25250 const ENCODED_LEN: usize = 243usize;
25251 fn deser(
25252 _version: MavlinkVersion,
25253 __input: &[u8],
25254 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25255 let avail_len = __input.len();
25256 let mut payload_buf = [0; Self::ENCODED_LEN];
25257 let mut buf = if avail_len < Self::ENCODED_LEN {
25258 payload_buf[0..avail_len].copy_from_slice(__input);
25259 Bytes::new(&payload_buf)
25260 } else {
25261 Bytes::new(__input)
25262 };
25263 let mut __struct = Self::default();
25264 __struct.request_id = buf.get_u8();
25265 __struct.uri_type = buf.get_u8();
25266 for v in &mut __struct.uri {
25267 let val = buf.get_u8();
25268 *v = val;
25269 }
25270 __struct.transfer_type = buf.get_u8();
25271 for v in &mut __struct.storage {
25272 let val = buf.get_u8();
25273 *v = val;
25274 }
25275 Ok(__struct)
25276 }
25277 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25278 let mut __tmp = BytesMut::new(bytes);
25279 #[allow(clippy::absurd_extreme_comparisons)]
25280 #[allow(unused_comparisons)]
25281 if __tmp.remaining() < Self::ENCODED_LEN {
25282 panic!(
25283 "buffer is too small (need {} bytes, but got {})",
25284 Self::ENCODED_LEN,
25285 __tmp.remaining(),
25286 )
25287 }
25288 __tmp.put_u8(self.request_id);
25289 __tmp.put_u8(self.uri_type);
25290 for val in &self.uri {
25291 __tmp.put_u8(*val);
25292 }
25293 __tmp.put_u8(self.transfer_type);
25294 for val in &self.storage {
25295 __tmp.put_u8(*val);
25296 }
25297 if matches!(version, MavlinkVersion::V2) {
25298 let len = __tmp.len();
25299 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25300 } else {
25301 __tmp.len()
25302 }
25303 }
25304}
25305#[doc = "id: 413"]
25306#[doc = "Response to a REQUEST_EVENT in case of an error (e.g. the event is not available anymore)."]
25307#[derive(Debug, Clone, PartialEq)]
25308#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25309#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25310pub struct RESPONSE_EVENT_ERROR_DATA {
25311 #[doc = "Sequence number."]
25312 pub sequence: u16,
25313 #[doc = "Oldest Sequence number that is still available after the sequence set in REQUEST_EVENT."]
25314 pub sequence_oldest_available: u16,
25315 #[doc = "System ID"]
25316 pub target_system: u8,
25317 #[doc = "Component ID"]
25318 pub target_component: u8,
25319 #[doc = "Error reason."]
25320 pub reason: MavEventErrorReason,
25321}
25322impl RESPONSE_EVENT_ERROR_DATA {
25323 pub const ENCODED_LEN: usize = 7usize;
25324 pub const DEFAULT: Self = Self {
25325 sequence: 0_u16,
25326 sequence_oldest_available: 0_u16,
25327 target_system: 0_u8,
25328 target_component: 0_u8,
25329 reason: MavEventErrorReason::DEFAULT,
25330 };
25331 #[cfg(feature = "arbitrary")]
25332 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25333 use arbitrary::{Arbitrary, Unstructured};
25334 let mut buf = [0u8; 1024];
25335 rng.fill_bytes(&mut buf);
25336 let mut unstructured = Unstructured::new(&buf);
25337 Self::arbitrary(&mut unstructured).unwrap_or_default()
25338 }
25339}
25340impl Default for RESPONSE_EVENT_ERROR_DATA {
25341 fn default() -> Self {
25342 Self::DEFAULT.clone()
25343 }
25344}
25345impl MessageData for RESPONSE_EVENT_ERROR_DATA {
25346 type Message = MavMessage;
25347 const ID: u32 = 413u32;
25348 const NAME: &'static str = "RESPONSE_EVENT_ERROR";
25349 const EXTRA_CRC: u8 = 77u8;
25350 const ENCODED_LEN: usize = 7usize;
25351 fn deser(
25352 _version: MavlinkVersion,
25353 __input: &[u8],
25354 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25355 let avail_len = __input.len();
25356 let mut payload_buf = [0; Self::ENCODED_LEN];
25357 let mut buf = if avail_len < Self::ENCODED_LEN {
25358 payload_buf[0..avail_len].copy_from_slice(__input);
25359 Bytes::new(&payload_buf)
25360 } else {
25361 Bytes::new(__input)
25362 };
25363 let mut __struct = Self::default();
25364 __struct.sequence = buf.get_u16_le();
25365 __struct.sequence_oldest_available = buf.get_u16_le();
25366 __struct.target_system = buf.get_u8();
25367 __struct.target_component = buf.get_u8();
25368 let tmp = buf.get_u8();
25369 __struct.reason =
25370 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
25371 enum_type: "MavEventErrorReason",
25372 value: tmp as u32,
25373 })?;
25374 Ok(__struct)
25375 }
25376 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25377 let mut __tmp = BytesMut::new(bytes);
25378 #[allow(clippy::absurd_extreme_comparisons)]
25379 #[allow(unused_comparisons)]
25380 if __tmp.remaining() < Self::ENCODED_LEN {
25381 panic!(
25382 "buffer is too small (need {} bytes, but got {})",
25383 Self::ENCODED_LEN,
25384 __tmp.remaining(),
25385 )
25386 }
25387 __tmp.put_u16_le(self.sequence);
25388 __tmp.put_u16_le(self.sequence_oldest_available);
25389 __tmp.put_u8(self.target_system);
25390 __tmp.put_u8(self.target_component);
25391 __tmp.put_u8(self.reason as u8);
25392 if matches!(version, MavlinkVersion::V2) {
25393 let len = __tmp.len();
25394 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25395 } else {
25396 __tmp.len()
25397 }
25398 }
25399}
25400#[doc = "id: 55"]
25401#[doc = "Read out the safety zone the MAV currently assumes."]
25402#[derive(Debug, Clone, PartialEq)]
25403#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25404#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25405pub struct SAFETY_ALLOWED_AREA_DATA {
25406 #[doc = "x position 1 / Latitude 1"]
25407 pub p1x: f32,
25408 #[doc = "y position 1 / Longitude 1"]
25409 pub p1y: f32,
25410 #[doc = "z position 1 / Altitude 1"]
25411 pub p1z: f32,
25412 #[doc = "x position 2 / Latitude 2"]
25413 pub p2x: f32,
25414 #[doc = "y position 2 / Longitude 2"]
25415 pub p2y: f32,
25416 #[doc = "z position 2 / Altitude 2"]
25417 pub p2z: f32,
25418 #[doc = "Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down."]
25419 pub frame: MavFrame,
25420}
25421impl SAFETY_ALLOWED_AREA_DATA {
25422 pub const ENCODED_LEN: usize = 25usize;
25423 pub const DEFAULT: Self = Self {
25424 p1x: 0.0_f32,
25425 p1y: 0.0_f32,
25426 p1z: 0.0_f32,
25427 p2x: 0.0_f32,
25428 p2y: 0.0_f32,
25429 p2z: 0.0_f32,
25430 frame: MavFrame::DEFAULT,
25431 };
25432 #[cfg(feature = "arbitrary")]
25433 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25434 use arbitrary::{Arbitrary, Unstructured};
25435 let mut buf = [0u8; 1024];
25436 rng.fill_bytes(&mut buf);
25437 let mut unstructured = Unstructured::new(&buf);
25438 Self::arbitrary(&mut unstructured).unwrap_or_default()
25439 }
25440}
25441impl Default for SAFETY_ALLOWED_AREA_DATA {
25442 fn default() -> Self {
25443 Self::DEFAULT.clone()
25444 }
25445}
25446impl MessageData for SAFETY_ALLOWED_AREA_DATA {
25447 type Message = MavMessage;
25448 const ID: u32 = 55u32;
25449 const NAME: &'static str = "SAFETY_ALLOWED_AREA";
25450 const EXTRA_CRC: u8 = 3u8;
25451 const ENCODED_LEN: usize = 25usize;
25452 fn deser(
25453 _version: MavlinkVersion,
25454 __input: &[u8],
25455 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25456 let avail_len = __input.len();
25457 let mut payload_buf = [0; Self::ENCODED_LEN];
25458 let mut buf = if avail_len < Self::ENCODED_LEN {
25459 payload_buf[0..avail_len].copy_from_slice(__input);
25460 Bytes::new(&payload_buf)
25461 } else {
25462 Bytes::new(__input)
25463 };
25464 let mut __struct = Self::default();
25465 __struct.p1x = buf.get_f32_le();
25466 __struct.p1y = buf.get_f32_le();
25467 __struct.p1z = buf.get_f32_le();
25468 __struct.p2x = buf.get_f32_le();
25469 __struct.p2y = buf.get_f32_le();
25470 __struct.p2z = buf.get_f32_le();
25471 let tmp = buf.get_u8();
25472 __struct.frame =
25473 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
25474 enum_type: "MavFrame",
25475 value: tmp as u32,
25476 })?;
25477 Ok(__struct)
25478 }
25479 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25480 let mut __tmp = BytesMut::new(bytes);
25481 #[allow(clippy::absurd_extreme_comparisons)]
25482 #[allow(unused_comparisons)]
25483 if __tmp.remaining() < Self::ENCODED_LEN {
25484 panic!(
25485 "buffer is too small (need {} bytes, but got {})",
25486 Self::ENCODED_LEN,
25487 __tmp.remaining(),
25488 )
25489 }
25490 __tmp.put_f32_le(self.p1x);
25491 __tmp.put_f32_le(self.p1y);
25492 __tmp.put_f32_le(self.p1z);
25493 __tmp.put_f32_le(self.p2x);
25494 __tmp.put_f32_le(self.p2y);
25495 __tmp.put_f32_le(self.p2z);
25496 __tmp.put_u8(self.frame as u8);
25497 if matches!(version, MavlinkVersion::V2) {
25498 let len = __tmp.len();
25499 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25500 } else {
25501 __tmp.len()
25502 }
25503 }
25504}
25505#[doc = "id: 54"]
25506#[doc = "Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations."]
25507#[derive(Debug, Clone, PartialEq)]
25508#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25509#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25510pub struct SAFETY_SET_ALLOWED_AREA_DATA {
25511 #[doc = "x position 1 / Latitude 1"]
25512 pub p1x: f32,
25513 #[doc = "y position 1 / Longitude 1"]
25514 pub p1y: f32,
25515 #[doc = "z position 1 / Altitude 1"]
25516 pub p1z: f32,
25517 #[doc = "x position 2 / Latitude 2"]
25518 pub p2x: f32,
25519 #[doc = "y position 2 / Longitude 2"]
25520 pub p2y: f32,
25521 #[doc = "z position 2 / Altitude 2"]
25522 pub p2z: f32,
25523 #[doc = "System ID"]
25524 pub target_system: u8,
25525 #[doc = "Component ID"]
25526 pub target_component: u8,
25527 #[doc = "Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down."]
25528 pub frame: MavFrame,
25529}
25530impl SAFETY_SET_ALLOWED_AREA_DATA {
25531 pub const ENCODED_LEN: usize = 27usize;
25532 pub const DEFAULT: Self = Self {
25533 p1x: 0.0_f32,
25534 p1y: 0.0_f32,
25535 p1z: 0.0_f32,
25536 p2x: 0.0_f32,
25537 p2y: 0.0_f32,
25538 p2z: 0.0_f32,
25539 target_system: 0_u8,
25540 target_component: 0_u8,
25541 frame: MavFrame::DEFAULT,
25542 };
25543 #[cfg(feature = "arbitrary")]
25544 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25545 use arbitrary::{Arbitrary, Unstructured};
25546 let mut buf = [0u8; 1024];
25547 rng.fill_bytes(&mut buf);
25548 let mut unstructured = Unstructured::new(&buf);
25549 Self::arbitrary(&mut unstructured).unwrap_or_default()
25550 }
25551}
25552impl Default for SAFETY_SET_ALLOWED_AREA_DATA {
25553 fn default() -> Self {
25554 Self::DEFAULT.clone()
25555 }
25556}
25557impl MessageData for SAFETY_SET_ALLOWED_AREA_DATA {
25558 type Message = MavMessage;
25559 const ID: u32 = 54u32;
25560 const NAME: &'static str = "SAFETY_SET_ALLOWED_AREA";
25561 const EXTRA_CRC: u8 = 15u8;
25562 const ENCODED_LEN: usize = 27usize;
25563 fn deser(
25564 _version: MavlinkVersion,
25565 __input: &[u8],
25566 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25567 let avail_len = __input.len();
25568 let mut payload_buf = [0; Self::ENCODED_LEN];
25569 let mut buf = if avail_len < Self::ENCODED_LEN {
25570 payload_buf[0..avail_len].copy_from_slice(__input);
25571 Bytes::new(&payload_buf)
25572 } else {
25573 Bytes::new(__input)
25574 };
25575 let mut __struct = Self::default();
25576 __struct.p1x = buf.get_f32_le();
25577 __struct.p1y = buf.get_f32_le();
25578 __struct.p1z = buf.get_f32_le();
25579 __struct.p2x = buf.get_f32_le();
25580 __struct.p2y = buf.get_f32_le();
25581 __struct.p2z = buf.get_f32_le();
25582 __struct.target_system = buf.get_u8();
25583 __struct.target_component = buf.get_u8();
25584 let tmp = buf.get_u8();
25585 __struct.frame =
25586 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
25587 enum_type: "MavFrame",
25588 value: tmp as u32,
25589 })?;
25590 Ok(__struct)
25591 }
25592 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25593 let mut __tmp = BytesMut::new(bytes);
25594 #[allow(clippy::absurd_extreme_comparisons)]
25595 #[allow(unused_comparisons)]
25596 if __tmp.remaining() < Self::ENCODED_LEN {
25597 panic!(
25598 "buffer is too small (need {} bytes, but got {})",
25599 Self::ENCODED_LEN,
25600 __tmp.remaining(),
25601 )
25602 }
25603 __tmp.put_f32_le(self.p1x);
25604 __tmp.put_f32_le(self.p1y);
25605 __tmp.put_f32_le(self.p1z);
25606 __tmp.put_f32_le(self.p2x);
25607 __tmp.put_f32_le(self.p2y);
25608 __tmp.put_f32_le(self.p2z);
25609 __tmp.put_u8(self.target_system);
25610 __tmp.put_u8(self.target_component);
25611 __tmp.put_u8(self.frame as u8);
25612 if matches!(version, MavlinkVersion::V2) {
25613 let len = __tmp.len();
25614 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25615 } else {
25616 __tmp.len()
25617 }
25618 }
25619}
25620#[doc = "id: 26"]
25621#[doc = "The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units."]
25622#[derive(Debug, Clone, PartialEq)]
25623#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25624#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25625pub struct SCALED_IMU_DATA {
25626 #[doc = "Timestamp (time since system boot)."]
25627 pub time_boot_ms: u32,
25628 #[doc = "X acceleration"]
25629 pub xacc: i16,
25630 #[doc = "Y acceleration"]
25631 pub yacc: i16,
25632 #[doc = "Z acceleration"]
25633 pub zacc: i16,
25634 #[doc = "Angular speed around X axis"]
25635 pub xgyro: i16,
25636 #[doc = "Angular speed around Y axis"]
25637 pub ygyro: i16,
25638 #[doc = "Angular speed around Z axis"]
25639 pub zgyro: i16,
25640 #[doc = "X Magnetic field"]
25641 pub xmag: i16,
25642 #[doc = "Y Magnetic field"]
25643 pub ymag: i16,
25644 #[doc = "Z Magnetic field"]
25645 pub zmag: i16,
25646 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
25647 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25648 pub temperature: i16,
25649}
25650impl SCALED_IMU_DATA {
25651 pub const ENCODED_LEN: usize = 24usize;
25652 pub const DEFAULT: Self = Self {
25653 time_boot_ms: 0_u32,
25654 xacc: 0_i16,
25655 yacc: 0_i16,
25656 zacc: 0_i16,
25657 xgyro: 0_i16,
25658 ygyro: 0_i16,
25659 zgyro: 0_i16,
25660 xmag: 0_i16,
25661 ymag: 0_i16,
25662 zmag: 0_i16,
25663 temperature: 0_i16,
25664 };
25665 #[cfg(feature = "arbitrary")]
25666 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25667 use arbitrary::{Arbitrary, Unstructured};
25668 let mut buf = [0u8; 1024];
25669 rng.fill_bytes(&mut buf);
25670 let mut unstructured = Unstructured::new(&buf);
25671 Self::arbitrary(&mut unstructured).unwrap_or_default()
25672 }
25673}
25674impl Default for SCALED_IMU_DATA {
25675 fn default() -> Self {
25676 Self::DEFAULT.clone()
25677 }
25678}
25679impl MessageData for SCALED_IMU_DATA {
25680 type Message = MavMessage;
25681 const ID: u32 = 26u32;
25682 const NAME: &'static str = "SCALED_IMU";
25683 const EXTRA_CRC: u8 = 170u8;
25684 const ENCODED_LEN: usize = 24usize;
25685 fn deser(
25686 _version: MavlinkVersion,
25687 __input: &[u8],
25688 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25689 let avail_len = __input.len();
25690 let mut payload_buf = [0; Self::ENCODED_LEN];
25691 let mut buf = if avail_len < Self::ENCODED_LEN {
25692 payload_buf[0..avail_len].copy_from_slice(__input);
25693 Bytes::new(&payload_buf)
25694 } else {
25695 Bytes::new(__input)
25696 };
25697 let mut __struct = Self::default();
25698 __struct.time_boot_ms = buf.get_u32_le();
25699 __struct.xacc = buf.get_i16_le();
25700 __struct.yacc = buf.get_i16_le();
25701 __struct.zacc = buf.get_i16_le();
25702 __struct.xgyro = buf.get_i16_le();
25703 __struct.ygyro = buf.get_i16_le();
25704 __struct.zgyro = buf.get_i16_le();
25705 __struct.xmag = buf.get_i16_le();
25706 __struct.ymag = buf.get_i16_le();
25707 __struct.zmag = buf.get_i16_le();
25708 __struct.temperature = buf.get_i16_le();
25709 Ok(__struct)
25710 }
25711 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25712 let mut __tmp = BytesMut::new(bytes);
25713 #[allow(clippy::absurd_extreme_comparisons)]
25714 #[allow(unused_comparisons)]
25715 if __tmp.remaining() < Self::ENCODED_LEN {
25716 panic!(
25717 "buffer is too small (need {} bytes, but got {})",
25718 Self::ENCODED_LEN,
25719 __tmp.remaining(),
25720 )
25721 }
25722 __tmp.put_u32_le(self.time_boot_ms);
25723 __tmp.put_i16_le(self.xacc);
25724 __tmp.put_i16_le(self.yacc);
25725 __tmp.put_i16_le(self.zacc);
25726 __tmp.put_i16_le(self.xgyro);
25727 __tmp.put_i16_le(self.ygyro);
25728 __tmp.put_i16_le(self.zgyro);
25729 __tmp.put_i16_le(self.xmag);
25730 __tmp.put_i16_le(self.ymag);
25731 __tmp.put_i16_le(self.zmag);
25732 __tmp.put_i16_le(self.temperature);
25733 if matches!(version, MavlinkVersion::V2) {
25734 let len = __tmp.len();
25735 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25736 } else {
25737 __tmp.len()
25738 }
25739 }
25740}
25741#[doc = "id: 116"]
25742#[doc = "The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units."]
25743#[derive(Debug, Clone, PartialEq)]
25744#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25745#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25746pub struct SCALED_IMU2_DATA {
25747 #[doc = "Timestamp (time since system boot)."]
25748 pub time_boot_ms: u32,
25749 #[doc = "X acceleration"]
25750 pub xacc: i16,
25751 #[doc = "Y acceleration"]
25752 pub yacc: i16,
25753 #[doc = "Z acceleration"]
25754 pub zacc: i16,
25755 #[doc = "Angular speed around X axis"]
25756 pub xgyro: i16,
25757 #[doc = "Angular speed around Y axis"]
25758 pub ygyro: i16,
25759 #[doc = "Angular speed around Z axis"]
25760 pub zgyro: i16,
25761 #[doc = "X Magnetic field"]
25762 pub xmag: i16,
25763 #[doc = "Y Magnetic field"]
25764 pub ymag: i16,
25765 #[doc = "Z Magnetic field"]
25766 pub zmag: i16,
25767 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
25768 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25769 pub temperature: i16,
25770}
25771impl SCALED_IMU2_DATA {
25772 pub const ENCODED_LEN: usize = 24usize;
25773 pub const DEFAULT: Self = Self {
25774 time_boot_ms: 0_u32,
25775 xacc: 0_i16,
25776 yacc: 0_i16,
25777 zacc: 0_i16,
25778 xgyro: 0_i16,
25779 ygyro: 0_i16,
25780 zgyro: 0_i16,
25781 xmag: 0_i16,
25782 ymag: 0_i16,
25783 zmag: 0_i16,
25784 temperature: 0_i16,
25785 };
25786 #[cfg(feature = "arbitrary")]
25787 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25788 use arbitrary::{Arbitrary, Unstructured};
25789 let mut buf = [0u8; 1024];
25790 rng.fill_bytes(&mut buf);
25791 let mut unstructured = Unstructured::new(&buf);
25792 Self::arbitrary(&mut unstructured).unwrap_or_default()
25793 }
25794}
25795impl Default for SCALED_IMU2_DATA {
25796 fn default() -> Self {
25797 Self::DEFAULT.clone()
25798 }
25799}
25800impl MessageData for SCALED_IMU2_DATA {
25801 type Message = MavMessage;
25802 const ID: u32 = 116u32;
25803 const NAME: &'static str = "SCALED_IMU2";
25804 const EXTRA_CRC: u8 = 76u8;
25805 const ENCODED_LEN: usize = 24usize;
25806 fn deser(
25807 _version: MavlinkVersion,
25808 __input: &[u8],
25809 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25810 let avail_len = __input.len();
25811 let mut payload_buf = [0; Self::ENCODED_LEN];
25812 let mut buf = if avail_len < Self::ENCODED_LEN {
25813 payload_buf[0..avail_len].copy_from_slice(__input);
25814 Bytes::new(&payload_buf)
25815 } else {
25816 Bytes::new(__input)
25817 };
25818 let mut __struct = Self::default();
25819 __struct.time_boot_ms = buf.get_u32_le();
25820 __struct.xacc = buf.get_i16_le();
25821 __struct.yacc = buf.get_i16_le();
25822 __struct.zacc = buf.get_i16_le();
25823 __struct.xgyro = buf.get_i16_le();
25824 __struct.ygyro = buf.get_i16_le();
25825 __struct.zgyro = buf.get_i16_le();
25826 __struct.xmag = buf.get_i16_le();
25827 __struct.ymag = buf.get_i16_le();
25828 __struct.zmag = buf.get_i16_le();
25829 __struct.temperature = buf.get_i16_le();
25830 Ok(__struct)
25831 }
25832 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25833 let mut __tmp = BytesMut::new(bytes);
25834 #[allow(clippy::absurd_extreme_comparisons)]
25835 #[allow(unused_comparisons)]
25836 if __tmp.remaining() < Self::ENCODED_LEN {
25837 panic!(
25838 "buffer is too small (need {} bytes, but got {})",
25839 Self::ENCODED_LEN,
25840 __tmp.remaining(),
25841 )
25842 }
25843 __tmp.put_u32_le(self.time_boot_ms);
25844 __tmp.put_i16_le(self.xacc);
25845 __tmp.put_i16_le(self.yacc);
25846 __tmp.put_i16_le(self.zacc);
25847 __tmp.put_i16_le(self.xgyro);
25848 __tmp.put_i16_le(self.ygyro);
25849 __tmp.put_i16_le(self.zgyro);
25850 __tmp.put_i16_le(self.xmag);
25851 __tmp.put_i16_le(self.ymag);
25852 __tmp.put_i16_le(self.zmag);
25853 __tmp.put_i16_le(self.temperature);
25854 if matches!(version, MavlinkVersion::V2) {
25855 let len = __tmp.len();
25856 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25857 } else {
25858 __tmp.len()
25859 }
25860 }
25861}
25862#[doc = "id: 129"]
25863#[doc = "The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units."]
25864#[derive(Debug, Clone, PartialEq)]
25865#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25866#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25867pub struct SCALED_IMU3_DATA {
25868 #[doc = "Timestamp (time since system boot)."]
25869 pub time_boot_ms: u32,
25870 #[doc = "X acceleration"]
25871 pub xacc: i16,
25872 #[doc = "Y acceleration"]
25873 pub yacc: i16,
25874 #[doc = "Z acceleration"]
25875 pub zacc: i16,
25876 #[doc = "Angular speed around X axis"]
25877 pub xgyro: i16,
25878 #[doc = "Angular speed around Y axis"]
25879 pub ygyro: i16,
25880 #[doc = "Angular speed around Z axis"]
25881 pub zgyro: i16,
25882 #[doc = "X Magnetic field"]
25883 pub xmag: i16,
25884 #[doc = "Y Magnetic field"]
25885 pub ymag: i16,
25886 #[doc = "Z Magnetic field"]
25887 pub zmag: i16,
25888 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
25889 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25890 pub temperature: i16,
25891}
25892impl SCALED_IMU3_DATA {
25893 pub const ENCODED_LEN: usize = 24usize;
25894 pub const DEFAULT: Self = Self {
25895 time_boot_ms: 0_u32,
25896 xacc: 0_i16,
25897 yacc: 0_i16,
25898 zacc: 0_i16,
25899 xgyro: 0_i16,
25900 ygyro: 0_i16,
25901 zgyro: 0_i16,
25902 xmag: 0_i16,
25903 ymag: 0_i16,
25904 zmag: 0_i16,
25905 temperature: 0_i16,
25906 };
25907 #[cfg(feature = "arbitrary")]
25908 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25909 use arbitrary::{Arbitrary, Unstructured};
25910 let mut buf = [0u8; 1024];
25911 rng.fill_bytes(&mut buf);
25912 let mut unstructured = Unstructured::new(&buf);
25913 Self::arbitrary(&mut unstructured).unwrap_or_default()
25914 }
25915}
25916impl Default for SCALED_IMU3_DATA {
25917 fn default() -> Self {
25918 Self::DEFAULT.clone()
25919 }
25920}
25921impl MessageData for SCALED_IMU3_DATA {
25922 type Message = MavMessage;
25923 const ID: u32 = 129u32;
25924 const NAME: &'static str = "SCALED_IMU3";
25925 const EXTRA_CRC: u8 = 46u8;
25926 const ENCODED_LEN: usize = 24usize;
25927 fn deser(
25928 _version: MavlinkVersion,
25929 __input: &[u8],
25930 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25931 let avail_len = __input.len();
25932 let mut payload_buf = [0; Self::ENCODED_LEN];
25933 let mut buf = if avail_len < Self::ENCODED_LEN {
25934 payload_buf[0..avail_len].copy_from_slice(__input);
25935 Bytes::new(&payload_buf)
25936 } else {
25937 Bytes::new(__input)
25938 };
25939 let mut __struct = Self::default();
25940 __struct.time_boot_ms = buf.get_u32_le();
25941 __struct.xacc = buf.get_i16_le();
25942 __struct.yacc = buf.get_i16_le();
25943 __struct.zacc = buf.get_i16_le();
25944 __struct.xgyro = buf.get_i16_le();
25945 __struct.ygyro = buf.get_i16_le();
25946 __struct.zgyro = buf.get_i16_le();
25947 __struct.xmag = buf.get_i16_le();
25948 __struct.ymag = buf.get_i16_le();
25949 __struct.zmag = buf.get_i16_le();
25950 __struct.temperature = buf.get_i16_le();
25951 Ok(__struct)
25952 }
25953 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25954 let mut __tmp = BytesMut::new(bytes);
25955 #[allow(clippy::absurd_extreme_comparisons)]
25956 #[allow(unused_comparisons)]
25957 if __tmp.remaining() < Self::ENCODED_LEN {
25958 panic!(
25959 "buffer is too small (need {} bytes, but got {})",
25960 Self::ENCODED_LEN,
25961 __tmp.remaining(),
25962 )
25963 }
25964 __tmp.put_u32_le(self.time_boot_ms);
25965 __tmp.put_i16_le(self.xacc);
25966 __tmp.put_i16_le(self.yacc);
25967 __tmp.put_i16_le(self.zacc);
25968 __tmp.put_i16_le(self.xgyro);
25969 __tmp.put_i16_le(self.ygyro);
25970 __tmp.put_i16_le(self.zgyro);
25971 __tmp.put_i16_le(self.xmag);
25972 __tmp.put_i16_le(self.ymag);
25973 __tmp.put_i16_le(self.zmag);
25974 __tmp.put_i16_le(self.temperature);
25975 if matches!(version, MavlinkVersion::V2) {
25976 let len = __tmp.len();
25977 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25978 } else {
25979 __tmp.len()
25980 }
25981 }
25982}
25983#[doc = "id: 29"]
25984#[doc = "The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field."]
25985#[derive(Debug, Clone, PartialEq)]
25986#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25987#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25988pub struct SCALED_PRESSURE_DATA {
25989 #[doc = "Timestamp (time since system boot)."]
25990 pub time_boot_ms: u32,
25991 #[doc = "Absolute pressure"]
25992 pub press_abs: f32,
25993 #[doc = "Differential pressure 1"]
25994 pub press_diff: f32,
25995 #[doc = "Absolute pressure temperature"]
25996 pub temperature: i16,
25997 #[doc = "Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC."]
25998 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25999 pub temperature_press_diff: i16,
26000}
26001impl SCALED_PRESSURE_DATA {
26002 pub const ENCODED_LEN: usize = 16usize;
26003 pub const DEFAULT: Self = Self {
26004 time_boot_ms: 0_u32,
26005 press_abs: 0.0_f32,
26006 press_diff: 0.0_f32,
26007 temperature: 0_i16,
26008 temperature_press_diff: 0_i16,
26009 };
26010 #[cfg(feature = "arbitrary")]
26011 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26012 use arbitrary::{Arbitrary, Unstructured};
26013 let mut buf = [0u8; 1024];
26014 rng.fill_bytes(&mut buf);
26015 let mut unstructured = Unstructured::new(&buf);
26016 Self::arbitrary(&mut unstructured).unwrap_or_default()
26017 }
26018}
26019impl Default for SCALED_PRESSURE_DATA {
26020 fn default() -> Self {
26021 Self::DEFAULT.clone()
26022 }
26023}
26024impl MessageData for SCALED_PRESSURE_DATA {
26025 type Message = MavMessage;
26026 const ID: u32 = 29u32;
26027 const NAME: &'static str = "SCALED_PRESSURE";
26028 const EXTRA_CRC: u8 = 115u8;
26029 const ENCODED_LEN: usize = 16usize;
26030 fn deser(
26031 _version: MavlinkVersion,
26032 __input: &[u8],
26033 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26034 let avail_len = __input.len();
26035 let mut payload_buf = [0; Self::ENCODED_LEN];
26036 let mut buf = if avail_len < Self::ENCODED_LEN {
26037 payload_buf[0..avail_len].copy_from_slice(__input);
26038 Bytes::new(&payload_buf)
26039 } else {
26040 Bytes::new(__input)
26041 };
26042 let mut __struct = Self::default();
26043 __struct.time_boot_ms = buf.get_u32_le();
26044 __struct.press_abs = buf.get_f32_le();
26045 __struct.press_diff = buf.get_f32_le();
26046 __struct.temperature = buf.get_i16_le();
26047 __struct.temperature_press_diff = buf.get_i16_le();
26048 Ok(__struct)
26049 }
26050 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26051 let mut __tmp = BytesMut::new(bytes);
26052 #[allow(clippy::absurd_extreme_comparisons)]
26053 #[allow(unused_comparisons)]
26054 if __tmp.remaining() < Self::ENCODED_LEN {
26055 panic!(
26056 "buffer is too small (need {} bytes, but got {})",
26057 Self::ENCODED_LEN,
26058 __tmp.remaining(),
26059 )
26060 }
26061 __tmp.put_u32_le(self.time_boot_ms);
26062 __tmp.put_f32_le(self.press_abs);
26063 __tmp.put_f32_le(self.press_diff);
26064 __tmp.put_i16_le(self.temperature);
26065 __tmp.put_i16_le(self.temperature_press_diff);
26066 if matches!(version, MavlinkVersion::V2) {
26067 let len = __tmp.len();
26068 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26069 } else {
26070 __tmp.len()
26071 }
26072 }
26073}
26074#[doc = "id: 137"]
26075#[doc = "Barometer readings for 2nd barometer."]
26076#[derive(Debug, Clone, PartialEq)]
26077#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26078#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26079pub struct SCALED_PRESSURE2_DATA {
26080 #[doc = "Timestamp (time since system boot)."]
26081 pub time_boot_ms: u32,
26082 #[doc = "Absolute pressure"]
26083 pub press_abs: f32,
26084 #[doc = "Differential pressure"]
26085 pub press_diff: f32,
26086 #[doc = "Absolute pressure temperature"]
26087 pub temperature: i16,
26088 #[doc = "Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC."]
26089 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26090 pub temperature_press_diff: i16,
26091}
26092impl SCALED_PRESSURE2_DATA {
26093 pub const ENCODED_LEN: usize = 16usize;
26094 pub const DEFAULT: Self = Self {
26095 time_boot_ms: 0_u32,
26096 press_abs: 0.0_f32,
26097 press_diff: 0.0_f32,
26098 temperature: 0_i16,
26099 temperature_press_diff: 0_i16,
26100 };
26101 #[cfg(feature = "arbitrary")]
26102 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26103 use arbitrary::{Arbitrary, Unstructured};
26104 let mut buf = [0u8; 1024];
26105 rng.fill_bytes(&mut buf);
26106 let mut unstructured = Unstructured::new(&buf);
26107 Self::arbitrary(&mut unstructured).unwrap_or_default()
26108 }
26109}
26110impl Default for SCALED_PRESSURE2_DATA {
26111 fn default() -> Self {
26112 Self::DEFAULT.clone()
26113 }
26114}
26115impl MessageData for SCALED_PRESSURE2_DATA {
26116 type Message = MavMessage;
26117 const ID: u32 = 137u32;
26118 const NAME: &'static str = "SCALED_PRESSURE2";
26119 const EXTRA_CRC: u8 = 195u8;
26120 const ENCODED_LEN: usize = 16usize;
26121 fn deser(
26122 _version: MavlinkVersion,
26123 __input: &[u8],
26124 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26125 let avail_len = __input.len();
26126 let mut payload_buf = [0; Self::ENCODED_LEN];
26127 let mut buf = if avail_len < Self::ENCODED_LEN {
26128 payload_buf[0..avail_len].copy_from_slice(__input);
26129 Bytes::new(&payload_buf)
26130 } else {
26131 Bytes::new(__input)
26132 };
26133 let mut __struct = Self::default();
26134 __struct.time_boot_ms = buf.get_u32_le();
26135 __struct.press_abs = buf.get_f32_le();
26136 __struct.press_diff = buf.get_f32_le();
26137 __struct.temperature = buf.get_i16_le();
26138 __struct.temperature_press_diff = buf.get_i16_le();
26139 Ok(__struct)
26140 }
26141 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26142 let mut __tmp = BytesMut::new(bytes);
26143 #[allow(clippy::absurd_extreme_comparisons)]
26144 #[allow(unused_comparisons)]
26145 if __tmp.remaining() < Self::ENCODED_LEN {
26146 panic!(
26147 "buffer is too small (need {} bytes, but got {})",
26148 Self::ENCODED_LEN,
26149 __tmp.remaining(),
26150 )
26151 }
26152 __tmp.put_u32_le(self.time_boot_ms);
26153 __tmp.put_f32_le(self.press_abs);
26154 __tmp.put_f32_le(self.press_diff);
26155 __tmp.put_i16_le(self.temperature);
26156 __tmp.put_i16_le(self.temperature_press_diff);
26157 if matches!(version, MavlinkVersion::V2) {
26158 let len = __tmp.len();
26159 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26160 } else {
26161 __tmp.len()
26162 }
26163 }
26164}
26165#[doc = "id: 143"]
26166#[doc = "Barometer readings for 3rd barometer."]
26167#[derive(Debug, Clone, PartialEq)]
26168#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26169#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26170pub struct SCALED_PRESSURE3_DATA {
26171 #[doc = "Timestamp (time since system boot)."]
26172 pub time_boot_ms: u32,
26173 #[doc = "Absolute pressure"]
26174 pub press_abs: f32,
26175 #[doc = "Differential pressure"]
26176 pub press_diff: f32,
26177 #[doc = "Absolute pressure temperature"]
26178 pub temperature: i16,
26179 #[doc = "Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC."]
26180 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26181 pub temperature_press_diff: i16,
26182}
26183impl SCALED_PRESSURE3_DATA {
26184 pub const ENCODED_LEN: usize = 16usize;
26185 pub const DEFAULT: Self = Self {
26186 time_boot_ms: 0_u32,
26187 press_abs: 0.0_f32,
26188 press_diff: 0.0_f32,
26189 temperature: 0_i16,
26190 temperature_press_diff: 0_i16,
26191 };
26192 #[cfg(feature = "arbitrary")]
26193 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26194 use arbitrary::{Arbitrary, Unstructured};
26195 let mut buf = [0u8; 1024];
26196 rng.fill_bytes(&mut buf);
26197 let mut unstructured = Unstructured::new(&buf);
26198 Self::arbitrary(&mut unstructured).unwrap_or_default()
26199 }
26200}
26201impl Default for SCALED_PRESSURE3_DATA {
26202 fn default() -> Self {
26203 Self::DEFAULT.clone()
26204 }
26205}
26206impl MessageData for SCALED_PRESSURE3_DATA {
26207 type Message = MavMessage;
26208 const ID: u32 = 143u32;
26209 const NAME: &'static str = "SCALED_PRESSURE3";
26210 const EXTRA_CRC: u8 = 131u8;
26211 const ENCODED_LEN: usize = 16usize;
26212 fn deser(
26213 _version: MavlinkVersion,
26214 __input: &[u8],
26215 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26216 let avail_len = __input.len();
26217 let mut payload_buf = [0; Self::ENCODED_LEN];
26218 let mut buf = if avail_len < Self::ENCODED_LEN {
26219 payload_buf[0..avail_len].copy_from_slice(__input);
26220 Bytes::new(&payload_buf)
26221 } else {
26222 Bytes::new(__input)
26223 };
26224 let mut __struct = Self::default();
26225 __struct.time_boot_ms = buf.get_u32_le();
26226 __struct.press_abs = buf.get_f32_le();
26227 __struct.press_diff = buf.get_f32_le();
26228 __struct.temperature = buf.get_i16_le();
26229 __struct.temperature_press_diff = buf.get_i16_le();
26230 Ok(__struct)
26231 }
26232 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26233 let mut __tmp = BytesMut::new(bytes);
26234 #[allow(clippy::absurd_extreme_comparisons)]
26235 #[allow(unused_comparisons)]
26236 if __tmp.remaining() < Self::ENCODED_LEN {
26237 panic!(
26238 "buffer is too small (need {} bytes, but got {})",
26239 Self::ENCODED_LEN,
26240 __tmp.remaining(),
26241 )
26242 }
26243 __tmp.put_u32_le(self.time_boot_ms);
26244 __tmp.put_f32_le(self.press_abs);
26245 __tmp.put_f32_le(self.press_diff);
26246 __tmp.put_i16_le(self.temperature);
26247 __tmp.put_i16_le(self.temperature_press_diff);
26248 if matches!(version, MavlinkVersion::V2) {
26249 let len = __tmp.len();
26250 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26251 } else {
26252 __tmp.len()
26253 }
26254 }
26255}
26256#[doc = "id: 126"]
26257#[doc = "Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate."]
26258#[derive(Debug, Clone, PartialEq)]
26259#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26260#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26261pub struct SERIAL_CONTROL_DATA {
26262 #[doc = "Baudrate of transfer. Zero means no change."]
26263 pub baudrate: u32,
26264 #[doc = "Timeout for reply data"]
26265 pub timeout: u16,
26266 #[doc = "Serial control device type."]
26267 pub device: SerialControlDev,
26268 #[doc = "Bitmap of serial control flags."]
26269 pub flags: SerialControlFlag,
26270 #[doc = "how many bytes in this transfer"]
26271 pub count: u8,
26272 #[doc = "serial data"]
26273 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26274 pub data: [u8; 70],
26275 #[doc = "System ID"]
26276 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26277 pub target_system: u8,
26278 #[doc = "Component ID"]
26279 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26280 pub target_component: u8,
26281}
26282impl SERIAL_CONTROL_DATA {
26283 pub const ENCODED_LEN: usize = 81usize;
26284 pub const DEFAULT: Self = Self {
26285 baudrate: 0_u32,
26286 timeout: 0_u16,
26287 device: SerialControlDev::DEFAULT,
26288 flags: SerialControlFlag::DEFAULT,
26289 count: 0_u8,
26290 data: [0_u8; 70usize],
26291 target_system: 0_u8,
26292 target_component: 0_u8,
26293 };
26294 #[cfg(feature = "arbitrary")]
26295 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26296 use arbitrary::{Arbitrary, Unstructured};
26297 let mut buf = [0u8; 1024];
26298 rng.fill_bytes(&mut buf);
26299 let mut unstructured = Unstructured::new(&buf);
26300 Self::arbitrary(&mut unstructured).unwrap_or_default()
26301 }
26302}
26303impl Default for SERIAL_CONTROL_DATA {
26304 fn default() -> Self {
26305 Self::DEFAULT.clone()
26306 }
26307}
26308impl MessageData for SERIAL_CONTROL_DATA {
26309 type Message = MavMessage;
26310 const ID: u32 = 126u32;
26311 const NAME: &'static str = "SERIAL_CONTROL";
26312 const EXTRA_CRC: u8 = 220u8;
26313 const ENCODED_LEN: usize = 81usize;
26314 fn deser(
26315 _version: MavlinkVersion,
26316 __input: &[u8],
26317 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26318 let avail_len = __input.len();
26319 let mut payload_buf = [0; Self::ENCODED_LEN];
26320 let mut buf = if avail_len < Self::ENCODED_LEN {
26321 payload_buf[0..avail_len].copy_from_slice(__input);
26322 Bytes::new(&payload_buf)
26323 } else {
26324 Bytes::new(__input)
26325 };
26326 let mut __struct = Self::default();
26327 __struct.baudrate = buf.get_u32_le();
26328 __struct.timeout = buf.get_u16_le();
26329 let tmp = buf.get_u8();
26330 __struct.device =
26331 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26332 enum_type: "SerialControlDev",
26333 value: tmp as u32,
26334 })?;
26335 let tmp = buf.get_u8();
26336 __struct.flags = SerialControlFlag::from_bits(tmp & SerialControlFlag::all().bits())
26337 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
26338 flag_type: "SerialControlFlag",
26339 value: tmp as u32,
26340 })?;
26341 __struct.count = buf.get_u8();
26342 for v in &mut __struct.data {
26343 let val = buf.get_u8();
26344 *v = val;
26345 }
26346 __struct.target_system = buf.get_u8();
26347 __struct.target_component = buf.get_u8();
26348 Ok(__struct)
26349 }
26350 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26351 let mut __tmp = BytesMut::new(bytes);
26352 #[allow(clippy::absurd_extreme_comparisons)]
26353 #[allow(unused_comparisons)]
26354 if __tmp.remaining() < Self::ENCODED_LEN {
26355 panic!(
26356 "buffer is too small (need {} bytes, but got {})",
26357 Self::ENCODED_LEN,
26358 __tmp.remaining(),
26359 )
26360 }
26361 __tmp.put_u32_le(self.baudrate);
26362 __tmp.put_u16_le(self.timeout);
26363 __tmp.put_u8(self.device as u8);
26364 __tmp.put_u8(self.flags.bits());
26365 __tmp.put_u8(self.count);
26366 for val in &self.data {
26367 __tmp.put_u8(*val);
26368 }
26369 __tmp.put_u8(self.target_system);
26370 __tmp.put_u8(self.target_component);
26371 if matches!(version, MavlinkVersion::V2) {
26372 let len = __tmp.len();
26373 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26374 } else {
26375 __tmp.len()
26376 }
26377 }
26378}
26379#[doc = "id: 36"]
26380#[doc = "Superseded by ACTUATOR_OUTPUT_STATUS. The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%."]
26381#[derive(Debug, Clone, PartialEq)]
26382#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26383#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26384pub struct SERVO_OUTPUT_RAW_DATA {
26385 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
26386 pub time_usec: u32,
26387 #[doc = "Servo output 1 value"]
26388 pub servo1_raw: u16,
26389 #[doc = "Servo output 2 value"]
26390 pub servo2_raw: u16,
26391 #[doc = "Servo output 3 value"]
26392 pub servo3_raw: u16,
26393 #[doc = "Servo output 4 value"]
26394 pub servo4_raw: u16,
26395 #[doc = "Servo output 5 value"]
26396 pub servo5_raw: u16,
26397 #[doc = "Servo output 6 value"]
26398 pub servo6_raw: u16,
26399 #[doc = "Servo output 7 value"]
26400 pub servo7_raw: u16,
26401 #[doc = "Servo output 8 value"]
26402 pub servo8_raw: u16,
26403 #[doc = "Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX."]
26404 pub port: u8,
26405 #[doc = "Servo output 9 value"]
26406 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26407 pub servo9_raw: u16,
26408 #[doc = "Servo output 10 value"]
26409 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26410 pub servo10_raw: u16,
26411 #[doc = "Servo output 11 value"]
26412 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26413 pub servo11_raw: u16,
26414 #[doc = "Servo output 12 value"]
26415 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26416 pub servo12_raw: u16,
26417 #[doc = "Servo output 13 value"]
26418 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26419 pub servo13_raw: u16,
26420 #[doc = "Servo output 14 value"]
26421 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26422 pub servo14_raw: u16,
26423 #[doc = "Servo output 15 value"]
26424 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26425 pub servo15_raw: u16,
26426 #[doc = "Servo output 16 value"]
26427 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26428 pub servo16_raw: u16,
26429}
26430impl SERVO_OUTPUT_RAW_DATA {
26431 pub const ENCODED_LEN: usize = 37usize;
26432 pub const DEFAULT: Self = Self {
26433 time_usec: 0_u32,
26434 servo1_raw: 0_u16,
26435 servo2_raw: 0_u16,
26436 servo3_raw: 0_u16,
26437 servo4_raw: 0_u16,
26438 servo5_raw: 0_u16,
26439 servo6_raw: 0_u16,
26440 servo7_raw: 0_u16,
26441 servo8_raw: 0_u16,
26442 port: 0_u8,
26443 servo9_raw: 0_u16,
26444 servo10_raw: 0_u16,
26445 servo11_raw: 0_u16,
26446 servo12_raw: 0_u16,
26447 servo13_raw: 0_u16,
26448 servo14_raw: 0_u16,
26449 servo15_raw: 0_u16,
26450 servo16_raw: 0_u16,
26451 };
26452 #[cfg(feature = "arbitrary")]
26453 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26454 use arbitrary::{Arbitrary, Unstructured};
26455 let mut buf = [0u8; 1024];
26456 rng.fill_bytes(&mut buf);
26457 let mut unstructured = Unstructured::new(&buf);
26458 Self::arbitrary(&mut unstructured).unwrap_or_default()
26459 }
26460}
26461impl Default for SERVO_OUTPUT_RAW_DATA {
26462 fn default() -> Self {
26463 Self::DEFAULT.clone()
26464 }
26465}
26466impl MessageData for SERVO_OUTPUT_RAW_DATA {
26467 type Message = MavMessage;
26468 const ID: u32 = 36u32;
26469 const NAME: &'static str = "SERVO_OUTPUT_RAW";
26470 const EXTRA_CRC: u8 = 222u8;
26471 const ENCODED_LEN: usize = 37usize;
26472 fn deser(
26473 _version: MavlinkVersion,
26474 __input: &[u8],
26475 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26476 let avail_len = __input.len();
26477 let mut payload_buf = [0; Self::ENCODED_LEN];
26478 let mut buf = if avail_len < Self::ENCODED_LEN {
26479 payload_buf[0..avail_len].copy_from_slice(__input);
26480 Bytes::new(&payload_buf)
26481 } else {
26482 Bytes::new(__input)
26483 };
26484 let mut __struct = Self::default();
26485 __struct.time_usec = buf.get_u32_le();
26486 __struct.servo1_raw = buf.get_u16_le();
26487 __struct.servo2_raw = buf.get_u16_le();
26488 __struct.servo3_raw = buf.get_u16_le();
26489 __struct.servo4_raw = buf.get_u16_le();
26490 __struct.servo5_raw = buf.get_u16_le();
26491 __struct.servo6_raw = buf.get_u16_le();
26492 __struct.servo7_raw = buf.get_u16_le();
26493 __struct.servo8_raw = buf.get_u16_le();
26494 __struct.port = buf.get_u8();
26495 __struct.servo9_raw = buf.get_u16_le();
26496 __struct.servo10_raw = buf.get_u16_le();
26497 __struct.servo11_raw = buf.get_u16_le();
26498 __struct.servo12_raw = buf.get_u16_le();
26499 __struct.servo13_raw = buf.get_u16_le();
26500 __struct.servo14_raw = buf.get_u16_le();
26501 __struct.servo15_raw = buf.get_u16_le();
26502 __struct.servo16_raw = buf.get_u16_le();
26503 Ok(__struct)
26504 }
26505 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26506 let mut __tmp = BytesMut::new(bytes);
26507 #[allow(clippy::absurd_extreme_comparisons)]
26508 #[allow(unused_comparisons)]
26509 if __tmp.remaining() < Self::ENCODED_LEN {
26510 panic!(
26511 "buffer is too small (need {} bytes, but got {})",
26512 Self::ENCODED_LEN,
26513 __tmp.remaining(),
26514 )
26515 }
26516 __tmp.put_u32_le(self.time_usec);
26517 __tmp.put_u16_le(self.servo1_raw);
26518 __tmp.put_u16_le(self.servo2_raw);
26519 __tmp.put_u16_le(self.servo3_raw);
26520 __tmp.put_u16_le(self.servo4_raw);
26521 __tmp.put_u16_le(self.servo5_raw);
26522 __tmp.put_u16_le(self.servo6_raw);
26523 __tmp.put_u16_le(self.servo7_raw);
26524 __tmp.put_u16_le(self.servo8_raw);
26525 __tmp.put_u8(self.port);
26526 __tmp.put_u16_le(self.servo9_raw);
26527 __tmp.put_u16_le(self.servo10_raw);
26528 __tmp.put_u16_le(self.servo11_raw);
26529 __tmp.put_u16_le(self.servo12_raw);
26530 __tmp.put_u16_le(self.servo13_raw);
26531 __tmp.put_u16_le(self.servo14_raw);
26532 __tmp.put_u16_le(self.servo15_raw);
26533 __tmp.put_u16_le(self.servo16_raw);
26534 if matches!(version, MavlinkVersion::V2) {
26535 let len = __tmp.len();
26536 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26537 } else {
26538 __tmp.len()
26539 }
26540 }
26541}
26542#[doc = "id: 256"]
26543#[doc = "Setup a MAVLink2 signing key. If called with secret_key of all zero and zero initial_timestamp will disable signing."]
26544#[derive(Debug, Clone, PartialEq)]
26545#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26546#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26547pub struct SETUP_SIGNING_DATA {
26548 #[doc = "initial timestamp"]
26549 pub initial_timestamp: u64,
26550 #[doc = "system id of the target"]
26551 pub target_system: u8,
26552 #[doc = "component ID of the target"]
26553 pub target_component: u8,
26554 #[doc = "signing key"]
26555 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26556 pub secret_key: [u8; 32],
26557}
26558impl SETUP_SIGNING_DATA {
26559 pub const ENCODED_LEN: usize = 42usize;
26560 pub const DEFAULT: Self = Self {
26561 initial_timestamp: 0_u64,
26562 target_system: 0_u8,
26563 target_component: 0_u8,
26564 secret_key: [0_u8; 32usize],
26565 };
26566 #[cfg(feature = "arbitrary")]
26567 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26568 use arbitrary::{Arbitrary, Unstructured};
26569 let mut buf = [0u8; 1024];
26570 rng.fill_bytes(&mut buf);
26571 let mut unstructured = Unstructured::new(&buf);
26572 Self::arbitrary(&mut unstructured).unwrap_or_default()
26573 }
26574}
26575impl Default for SETUP_SIGNING_DATA {
26576 fn default() -> Self {
26577 Self::DEFAULT.clone()
26578 }
26579}
26580impl MessageData for SETUP_SIGNING_DATA {
26581 type Message = MavMessage;
26582 const ID: u32 = 256u32;
26583 const NAME: &'static str = "SETUP_SIGNING";
26584 const EXTRA_CRC: u8 = 71u8;
26585 const ENCODED_LEN: usize = 42usize;
26586 fn deser(
26587 _version: MavlinkVersion,
26588 __input: &[u8],
26589 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26590 let avail_len = __input.len();
26591 let mut payload_buf = [0; Self::ENCODED_LEN];
26592 let mut buf = if avail_len < Self::ENCODED_LEN {
26593 payload_buf[0..avail_len].copy_from_slice(__input);
26594 Bytes::new(&payload_buf)
26595 } else {
26596 Bytes::new(__input)
26597 };
26598 let mut __struct = Self::default();
26599 __struct.initial_timestamp = buf.get_u64_le();
26600 __struct.target_system = buf.get_u8();
26601 __struct.target_component = buf.get_u8();
26602 for v in &mut __struct.secret_key {
26603 let val = buf.get_u8();
26604 *v = val;
26605 }
26606 Ok(__struct)
26607 }
26608 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26609 let mut __tmp = BytesMut::new(bytes);
26610 #[allow(clippy::absurd_extreme_comparisons)]
26611 #[allow(unused_comparisons)]
26612 if __tmp.remaining() < Self::ENCODED_LEN {
26613 panic!(
26614 "buffer is too small (need {} bytes, but got {})",
26615 Self::ENCODED_LEN,
26616 __tmp.remaining(),
26617 )
26618 }
26619 __tmp.put_u64_le(self.initial_timestamp);
26620 __tmp.put_u8(self.target_system);
26621 __tmp.put_u8(self.target_component);
26622 for val in &self.secret_key {
26623 __tmp.put_u8(*val);
26624 }
26625 if matches!(version, MavlinkVersion::V2) {
26626 let len = __tmp.len();
26627 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26628 } else {
26629 __tmp.len()
26630 }
26631 }
26632}
26633#[doc = "id: 139"]
26634#[doc = "Set the vehicle attitude and body angular rates."]
26635#[derive(Debug, Clone, PartialEq)]
26636#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26637#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26638pub struct SET_ACTUATOR_CONTROL_TARGET_DATA {
26639 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
26640 pub time_usec: u64,
26641 #[doc = "Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs."]
26642 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26643 pub controls: [f32; 8],
26644 #[doc = "Actuator group. The \"_mlx\" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances."]
26645 pub group_mlx: u8,
26646 #[doc = "System ID"]
26647 pub target_system: u8,
26648 #[doc = "Component ID"]
26649 pub target_component: u8,
26650}
26651impl SET_ACTUATOR_CONTROL_TARGET_DATA {
26652 pub const ENCODED_LEN: usize = 43usize;
26653 pub const DEFAULT: Self = Self {
26654 time_usec: 0_u64,
26655 controls: [0.0_f32; 8usize],
26656 group_mlx: 0_u8,
26657 target_system: 0_u8,
26658 target_component: 0_u8,
26659 };
26660 #[cfg(feature = "arbitrary")]
26661 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26662 use arbitrary::{Arbitrary, Unstructured};
26663 let mut buf = [0u8; 1024];
26664 rng.fill_bytes(&mut buf);
26665 let mut unstructured = Unstructured::new(&buf);
26666 Self::arbitrary(&mut unstructured).unwrap_or_default()
26667 }
26668}
26669impl Default for SET_ACTUATOR_CONTROL_TARGET_DATA {
26670 fn default() -> Self {
26671 Self::DEFAULT.clone()
26672 }
26673}
26674impl MessageData for SET_ACTUATOR_CONTROL_TARGET_DATA {
26675 type Message = MavMessage;
26676 const ID: u32 = 139u32;
26677 const NAME: &'static str = "SET_ACTUATOR_CONTROL_TARGET";
26678 const EXTRA_CRC: u8 = 168u8;
26679 const ENCODED_LEN: usize = 43usize;
26680 fn deser(
26681 _version: MavlinkVersion,
26682 __input: &[u8],
26683 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26684 let avail_len = __input.len();
26685 let mut payload_buf = [0; Self::ENCODED_LEN];
26686 let mut buf = if avail_len < Self::ENCODED_LEN {
26687 payload_buf[0..avail_len].copy_from_slice(__input);
26688 Bytes::new(&payload_buf)
26689 } else {
26690 Bytes::new(__input)
26691 };
26692 let mut __struct = Self::default();
26693 __struct.time_usec = buf.get_u64_le();
26694 for v in &mut __struct.controls {
26695 let val = buf.get_f32_le();
26696 *v = val;
26697 }
26698 __struct.group_mlx = buf.get_u8();
26699 __struct.target_system = buf.get_u8();
26700 __struct.target_component = buf.get_u8();
26701 Ok(__struct)
26702 }
26703 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26704 let mut __tmp = BytesMut::new(bytes);
26705 #[allow(clippy::absurd_extreme_comparisons)]
26706 #[allow(unused_comparisons)]
26707 if __tmp.remaining() < Self::ENCODED_LEN {
26708 panic!(
26709 "buffer is too small (need {} bytes, but got {})",
26710 Self::ENCODED_LEN,
26711 __tmp.remaining(),
26712 )
26713 }
26714 __tmp.put_u64_le(self.time_usec);
26715 for val in &self.controls {
26716 __tmp.put_f32_le(*val);
26717 }
26718 __tmp.put_u8(self.group_mlx);
26719 __tmp.put_u8(self.target_system);
26720 __tmp.put_u8(self.target_component);
26721 if matches!(version, MavlinkVersion::V2) {
26722 let len = __tmp.len();
26723 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26724 } else {
26725 __tmp.len()
26726 }
26727 }
26728}
26729#[doc = "id: 82"]
26730#[doc = "Sets a desired vehicle attitude. Used by an external controller to command the vehicle (manual controller or other system)."]
26731#[derive(Debug, Clone, PartialEq)]
26732#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26733#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26734pub struct SET_ATTITUDE_TARGET_DATA {
26735 #[doc = "Timestamp (time since system boot)."]
26736 pub time_boot_ms: u32,
26737 #[doc = "Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) from MAV_FRAME_LOCAL_NED to MAV_FRAME_BODY_FRD"]
26738 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26739 pub q: [f32; 4],
26740 #[doc = "Body roll rate"]
26741 pub body_roll_rate: f32,
26742 #[doc = "Body pitch rate"]
26743 pub body_pitch_rate: f32,
26744 #[doc = "Body yaw rate"]
26745 pub body_yaw_rate: f32,
26746 #[doc = "Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)"]
26747 pub thrust: f32,
26748 #[doc = "System ID"]
26749 pub target_system: u8,
26750 #[doc = "Component ID"]
26751 pub target_component: u8,
26752 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
26753 pub type_mask: AttitudeTargetTypemask,
26754 #[doc = "3D thrust setpoint in the body NED frame, normalized to -1 .. 1"]
26755 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26756 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26757 pub thrust_body: [f32; 3],
26758}
26759impl SET_ATTITUDE_TARGET_DATA {
26760 pub const ENCODED_LEN: usize = 51usize;
26761 pub const DEFAULT: Self = Self {
26762 time_boot_ms: 0_u32,
26763 q: [0.0_f32; 4usize],
26764 body_roll_rate: 0.0_f32,
26765 body_pitch_rate: 0.0_f32,
26766 body_yaw_rate: 0.0_f32,
26767 thrust: 0.0_f32,
26768 target_system: 0_u8,
26769 target_component: 0_u8,
26770 type_mask: AttitudeTargetTypemask::DEFAULT,
26771 thrust_body: [0.0_f32; 3usize],
26772 };
26773 #[cfg(feature = "arbitrary")]
26774 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26775 use arbitrary::{Arbitrary, Unstructured};
26776 let mut buf = [0u8; 1024];
26777 rng.fill_bytes(&mut buf);
26778 let mut unstructured = Unstructured::new(&buf);
26779 Self::arbitrary(&mut unstructured).unwrap_or_default()
26780 }
26781}
26782impl Default for SET_ATTITUDE_TARGET_DATA {
26783 fn default() -> Self {
26784 Self::DEFAULT.clone()
26785 }
26786}
26787impl MessageData for SET_ATTITUDE_TARGET_DATA {
26788 type Message = MavMessage;
26789 const ID: u32 = 82u32;
26790 const NAME: &'static str = "SET_ATTITUDE_TARGET";
26791 const EXTRA_CRC: u8 = 49u8;
26792 const ENCODED_LEN: usize = 51usize;
26793 fn deser(
26794 _version: MavlinkVersion,
26795 __input: &[u8],
26796 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26797 let avail_len = __input.len();
26798 let mut payload_buf = [0; Self::ENCODED_LEN];
26799 let mut buf = if avail_len < Self::ENCODED_LEN {
26800 payload_buf[0..avail_len].copy_from_slice(__input);
26801 Bytes::new(&payload_buf)
26802 } else {
26803 Bytes::new(__input)
26804 };
26805 let mut __struct = Self::default();
26806 __struct.time_boot_ms = buf.get_u32_le();
26807 for v in &mut __struct.q {
26808 let val = buf.get_f32_le();
26809 *v = val;
26810 }
26811 __struct.body_roll_rate = buf.get_f32_le();
26812 __struct.body_pitch_rate = buf.get_f32_le();
26813 __struct.body_yaw_rate = buf.get_f32_le();
26814 __struct.thrust = buf.get_f32_le();
26815 __struct.target_system = buf.get_u8();
26816 __struct.target_component = buf.get_u8();
26817 let tmp = buf.get_u8();
26818 __struct.type_mask = AttitudeTargetTypemask::from_bits(
26819 tmp & AttitudeTargetTypemask::all().bits(),
26820 )
26821 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
26822 flag_type: "AttitudeTargetTypemask",
26823 value: tmp as u32,
26824 })?;
26825 for v in &mut __struct.thrust_body {
26826 let val = buf.get_f32_le();
26827 *v = val;
26828 }
26829 Ok(__struct)
26830 }
26831 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26832 let mut __tmp = BytesMut::new(bytes);
26833 #[allow(clippy::absurd_extreme_comparisons)]
26834 #[allow(unused_comparisons)]
26835 if __tmp.remaining() < Self::ENCODED_LEN {
26836 panic!(
26837 "buffer is too small (need {} bytes, but got {})",
26838 Self::ENCODED_LEN,
26839 __tmp.remaining(),
26840 )
26841 }
26842 __tmp.put_u32_le(self.time_boot_ms);
26843 for val in &self.q {
26844 __tmp.put_f32_le(*val);
26845 }
26846 __tmp.put_f32_le(self.body_roll_rate);
26847 __tmp.put_f32_le(self.body_pitch_rate);
26848 __tmp.put_f32_le(self.body_yaw_rate);
26849 __tmp.put_f32_le(self.thrust);
26850 __tmp.put_u8(self.target_system);
26851 __tmp.put_u8(self.target_component);
26852 __tmp.put_u8(self.type_mask.bits());
26853 for val in &self.thrust_body {
26854 __tmp.put_f32_le(*val);
26855 }
26856 if matches!(version, MavlinkVersion::V2) {
26857 let len = __tmp.len();
26858 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26859 } else {
26860 __tmp.len()
26861 }
26862 }
26863}
26864#[doc = "id: 48"]
26865#[doc = "Sets the GPS coordinates of the vehicle local origin (0,0,0) position. Vehicle should emit GPS_GLOBAL_ORIGIN irrespective of whether the origin is changed. This enables transform between the local coordinate frame and the global (GPS) coordinate frame, which may be necessary when (for example) indoor and outdoor settings are connected and the MAV should move from in- to outdoor."]
26866#[derive(Debug, Clone, PartialEq)]
26867#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26868#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26869pub struct SET_GPS_GLOBAL_ORIGIN_DATA {
26870 #[doc = "Latitude (WGS84)"]
26871 pub latitude: i32,
26872 #[doc = "Longitude (WGS84)"]
26873 pub longitude: i32,
26874 #[doc = "Altitude (MSL). Positive for up."]
26875 pub altitude: i32,
26876 #[doc = "System ID"]
26877 pub target_system: u8,
26878 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
26879 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26880 pub time_usec: u64,
26881}
26882impl SET_GPS_GLOBAL_ORIGIN_DATA {
26883 pub const ENCODED_LEN: usize = 21usize;
26884 pub const DEFAULT: Self = Self {
26885 latitude: 0_i32,
26886 longitude: 0_i32,
26887 altitude: 0_i32,
26888 target_system: 0_u8,
26889 time_usec: 0_u64,
26890 };
26891 #[cfg(feature = "arbitrary")]
26892 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26893 use arbitrary::{Arbitrary, Unstructured};
26894 let mut buf = [0u8; 1024];
26895 rng.fill_bytes(&mut buf);
26896 let mut unstructured = Unstructured::new(&buf);
26897 Self::arbitrary(&mut unstructured).unwrap_or_default()
26898 }
26899}
26900impl Default for SET_GPS_GLOBAL_ORIGIN_DATA {
26901 fn default() -> Self {
26902 Self::DEFAULT.clone()
26903 }
26904}
26905impl MessageData for SET_GPS_GLOBAL_ORIGIN_DATA {
26906 type Message = MavMessage;
26907 const ID: u32 = 48u32;
26908 const NAME: &'static str = "SET_GPS_GLOBAL_ORIGIN";
26909 const EXTRA_CRC: u8 = 41u8;
26910 const ENCODED_LEN: usize = 21usize;
26911 fn deser(
26912 _version: MavlinkVersion,
26913 __input: &[u8],
26914 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26915 let avail_len = __input.len();
26916 let mut payload_buf = [0; Self::ENCODED_LEN];
26917 let mut buf = if avail_len < Self::ENCODED_LEN {
26918 payload_buf[0..avail_len].copy_from_slice(__input);
26919 Bytes::new(&payload_buf)
26920 } else {
26921 Bytes::new(__input)
26922 };
26923 let mut __struct = Self::default();
26924 __struct.latitude = buf.get_i32_le();
26925 __struct.longitude = buf.get_i32_le();
26926 __struct.altitude = buf.get_i32_le();
26927 __struct.target_system = buf.get_u8();
26928 __struct.time_usec = buf.get_u64_le();
26929 Ok(__struct)
26930 }
26931 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26932 let mut __tmp = BytesMut::new(bytes);
26933 #[allow(clippy::absurd_extreme_comparisons)]
26934 #[allow(unused_comparisons)]
26935 if __tmp.remaining() < Self::ENCODED_LEN {
26936 panic!(
26937 "buffer is too small (need {} bytes, but got {})",
26938 Self::ENCODED_LEN,
26939 __tmp.remaining(),
26940 )
26941 }
26942 __tmp.put_i32_le(self.latitude);
26943 __tmp.put_i32_le(self.longitude);
26944 __tmp.put_i32_le(self.altitude);
26945 __tmp.put_u8(self.target_system);
26946 __tmp.put_u64_le(self.time_usec);
26947 if matches!(version, MavlinkVersion::V2) {
26948 let len = __tmp.len();
26949 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26950 } else {
26951 __tmp.len()
26952 }
26953 }
26954}
26955#[doc = "id: 243"]
26956#[doc = "Sets the home position. \tThe home position is the default position that the system will return to and land on. The position is set automatically by the system during the takeoff (and may also be set using this message). The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242)."]
26957#[derive(Debug, Clone, PartialEq)]
26958#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26959#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26960pub struct SET_HOME_POSITION_DATA {
26961 #[doc = "Latitude (WGS84)"]
26962 pub latitude: i32,
26963 #[doc = "Longitude (WGS84)"]
26964 pub longitude: i32,
26965 #[doc = "Altitude (MSL). Positive for up."]
26966 pub altitude: i32,
26967 #[doc = "Local X position of this position in the local coordinate frame (NED)"]
26968 pub x: f32,
26969 #[doc = "Local Y position of this position in the local coordinate frame (NED)"]
26970 pub y: f32,
26971 #[doc = "Local Z position of this position in the local coordinate frame (NED: positive \"down\")"]
26972 pub z: f32,
26973 #[doc = "World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground"]
26974 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26975 pub q: [f32; 4],
26976 #[doc = "Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
26977 pub approach_x: f32,
26978 #[doc = "Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
26979 pub approach_y: f32,
26980 #[doc = "Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
26981 pub approach_z: f32,
26982 #[doc = "System ID."]
26983 pub target_system: u8,
26984 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
26985 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26986 pub time_usec: u64,
26987}
26988impl SET_HOME_POSITION_DATA {
26989 pub const ENCODED_LEN: usize = 61usize;
26990 pub const DEFAULT: Self = Self {
26991 latitude: 0_i32,
26992 longitude: 0_i32,
26993 altitude: 0_i32,
26994 x: 0.0_f32,
26995 y: 0.0_f32,
26996 z: 0.0_f32,
26997 q: [0.0_f32; 4usize],
26998 approach_x: 0.0_f32,
26999 approach_y: 0.0_f32,
27000 approach_z: 0.0_f32,
27001 target_system: 0_u8,
27002 time_usec: 0_u64,
27003 };
27004 #[cfg(feature = "arbitrary")]
27005 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27006 use arbitrary::{Arbitrary, Unstructured};
27007 let mut buf = [0u8; 1024];
27008 rng.fill_bytes(&mut buf);
27009 let mut unstructured = Unstructured::new(&buf);
27010 Self::arbitrary(&mut unstructured).unwrap_or_default()
27011 }
27012}
27013impl Default for SET_HOME_POSITION_DATA {
27014 fn default() -> Self {
27015 Self::DEFAULT.clone()
27016 }
27017}
27018impl MessageData for SET_HOME_POSITION_DATA {
27019 type Message = MavMessage;
27020 const ID: u32 = 243u32;
27021 const NAME: &'static str = "SET_HOME_POSITION";
27022 const EXTRA_CRC: u8 = 85u8;
27023 const ENCODED_LEN: usize = 61usize;
27024 fn deser(
27025 _version: MavlinkVersion,
27026 __input: &[u8],
27027 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27028 let avail_len = __input.len();
27029 let mut payload_buf = [0; Self::ENCODED_LEN];
27030 let mut buf = if avail_len < Self::ENCODED_LEN {
27031 payload_buf[0..avail_len].copy_from_slice(__input);
27032 Bytes::new(&payload_buf)
27033 } else {
27034 Bytes::new(__input)
27035 };
27036 let mut __struct = Self::default();
27037 __struct.latitude = buf.get_i32_le();
27038 __struct.longitude = buf.get_i32_le();
27039 __struct.altitude = buf.get_i32_le();
27040 __struct.x = buf.get_f32_le();
27041 __struct.y = buf.get_f32_le();
27042 __struct.z = buf.get_f32_le();
27043 for v in &mut __struct.q {
27044 let val = buf.get_f32_le();
27045 *v = val;
27046 }
27047 __struct.approach_x = buf.get_f32_le();
27048 __struct.approach_y = buf.get_f32_le();
27049 __struct.approach_z = buf.get_f32_le();
27050 __struct.target_system = buf.get_u8();
27051 __struct.time_usec = buf.get_u64_le();
27052 Ok(__struct)
27053 }
27054 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27055 let mut __tmp = BytesMut::new(bytes);
27056 #[allow(clippy::absurd_extreme_comparisons)]
27057 #[allow(unused_comparisons)]
27058 if __tmp.remaining() < Self::ENCODED_LEN {
27059 panic!(
27060 "buffer is too small (need {} bytes, but got {})",
27061 Self::ENCODED_LEN,
27062 __tmp.remaining(),
27063 )
27064 }
27065 __tmp.put_i32_le(self.latitude);
27066 __tmp.put_i32_le(self.longitude);
27067 __tmp.put_i32_le(self.altitude);
27068 __tmp.put_f32_le(self.x);
27069 __tmp.put_f32_le(self.y);
27070 __tmp.put_f32_le(self.z);
27071 for val in &self.q {
27072 __tmp.put_f32_le(*val);
27073 }
27074 __tmp.put_f32_le(self.approach_x);
27075 __tmp.put_f32_le(self.approach_y);
27076 __tmp.put_f32_le(self.approach_z);
27077 __tmp.put_u8(self.target_system);
27078 __tmp.put_u64_le(self.time_usec);
27079 if matches!(version, MavlinkVersion::V2) {
27080 let len = __tmp.len();
27081 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27082 } else {
27083 __tmp.len()
27084 }
27085 }
27086}
27087#[doc = "id: 11"]
27088#[doc = "Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component."]
27089#[derive(Debug, Clone, PartialEq)]
27090#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27091#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27092pub struct SET_MODE_DATA {
27093 #[doc = "The new autopilot-specific mode. This field can be ignored by an autopilot."]
27094 pub custom_mode: u32,
27095 #[doc = "The system setting the mode"]
27096 pub target_system: u8,
27097 #[doc = "The new base mode."]
27098 pub base_mode: MavMode,
27099}
27100impl SET_MODE_DATA {
27101 pub const ENCODED_LEN: usize = 6usize;
27102 pub const DEFAULT: Self = Self {
27103 custom_mode: 0_u32,
27104 target_system: 0_u8,
27105 base_mode: MavMode::DEFAULT,
27106 };
27107 #[cfg(feature = "arbitrary")]
27108 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27109 use arbitrary::{Arbitrary, Unstructured};
27110 let mut buf = [0u8; 1024];
27111 rng.fill_bytes(&mut buf);
27112 let mut unstructured = Unstructured::new(&buf);
27113 Self::arbitrary(&mut unstructured).unwrap_or_default()
27114 }
27115}
27116impl Default for SET_MODE_DATA {
27117 fn default() -> Self {
27118 Self::DEFAULT.clone()
27119 }
27120}
27121impl MessageData for SET_MODE_DATA {
27122 type Message = MavMessage;
27123 const ID: u32 = 11u32;
27124 const NAME: &'static str = "SET_MODE";
27125 const EXTRA_CRC: u8 = 89u8;
27126 const ENCODED_LEN: usize = 6usize;
27127 fn deser(
27128 _version: MavlinkVersion,
27129 __input: &[u8],
27130 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27131 let avail_len = __input.len();
27132 let mut payload_buf = [0; Self::ENCODED_LEN];
27133 let mut buf = if avail_len < Self::ENCODED_LEN {
27134 payload_buf[0..avail_len].copy_from_slice(__input);
27135 Bytes::new(&payload_buf)
27136 } else {
27137 Bytes::new(__input)
27138 };
27139 let mut __struct = Self::default();
27140 __struct.custom_mode = buf.get_u32_le();
27141 __struct.target_system = buf.get_u8();
27142 let tmp = buf.get_u8();
27143 __struct.base_mode =
27144 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
27145 enum_type: "MavMode",
27146 value: tmp as u32,
27147 })?;
27148 Ok(__struct)
27149 }
27150 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27151 let mut __tmp = BytesMut::new(bytes);
27152 #[allow(clippy::absurd_extreme_comparisons)]
27153 #[allow(unused_comparisons)]
27154 if __tmp.remaining() < Self::ENCODED_LEN {
27155 panic!(
27156 "buffer is too small (need {} bytes, but got {})",
27157 Self::ENCODED_LEN,
27158 __tmp.remaining(),
27159 )
27160 }
27161 __tmp.put_u32_le(self.custom_mode);
27162 __tmp.put_u8(self.target_system);
27163 __tmp.put_u8(self.base_mode as u8);
27164 if matches!(version, MavlinkVersion::V2) {
27165 let len = __tmp.len();
27166 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27167 } else {
27168 __tmp.len()
27169 }
27170 }
27171}
27172#[doc = "id: 86"]
27173#[doc = "Sets a desired vehicle position, velocity, and/or acceleration in a global coordinate system (WGS84). Used by an external controller to command the vehicle (manual controller or other system)."]
27174#[derive(Debug, Clone, PartialEq)]
27175#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27176#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27177pub struct SET_POSITION_TARGET_GLOBAL_INT_DATA {
27178 #[doc = "Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency."]
27179 pub time_boot_ms: u32,
27180 #[doc = "Latitude in WGS84 frame"]
27181 pub lat_int: i32,
27182 #[doc = "Longitude in WGS84 frame"]
27183 pub lon_int: i32,
27184 #[doc = "Altitude (MSL, Relative to home, or AGL - depending on frame)"]
27185 pub alt: f32,
27186 #[doc = "X velocity in NED frame"]
27187 pub vx: f32,
27188 #[doc = "Y velocity in NED frame"]
27189 pub vy: f32,
27190 #[doc = "Z velocity in NED frame"]
27191 pub vz: f32,
27192 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
27193 pub afx: f32,
27194 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
27195 pub afy: f32,
27196 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
27197 pub afz: f32,
27198 #[doc = "yaw setpoint"]
27199 pub yaw: f32,
27200 #[doc = "yaw rate setpoint"]
27201 pub yaw_rate: f32,
27202 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
27203 pub type_mask: PositionTargetTypemask,
27204 #[doc = "System ID"]
27205 pub target_system: u8,
27206 #[doc = "Component ID"]
27207 pub target_component: u8,
27208 #[doc = "Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated)"]
27209 pub coordinate_frame: MavFrame,
27210}
27211impl SET_POSITION_TARGET_GLOBAL_INT_DATA {
27212 pub const ENCODED_LEN: usize = 53usize;
27213 pub const DEFAULT: Self = Self {
27214 time_boot_ms: 0_u32,
27215 lat_int: 0_i32,
27216 lon_int: 0_i32,
27217 alt: 0.0_f32,
27218 vx: 0.0_f32,
27219 vy: 0.0_f32,
27220 vz: 0.0_f32,
27221 afx: 0.0_f32,
27222 afy: 0.0_f32,
27223 afz: 0.0_f32,
27224 yaw: 0.0_f32,
27225 yaw_rate: 0.0_f32,
27226 type_mask: PositionTargetTypemask::DEFAULT,
27227 target_system: 0_u8,
27228 target_component: 0_u8,
27229 coordinate_frame: MavFrame::DEFAULT,
27230 };
27231 #[cfg(feature = "arbitrary")]
27232 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27233 use arbitrary::{Arbitrary, Unstructured};
27234 let mut buf = [0u8; 1024];
27235 rng.fill_bytes(&mut buf);
27236 let mut unstructured = Unstructured::new(&buf);
27237 Self::arbitrary(&mut unstructured).unwrap_or_default()
27238 }
27239}
27240impl Default for SET_POSITION_TARGET_GLOBAL_INT_DATA {
27241 fn default() -> Self {
27242 Self::DEFAULT.clone()
27243 }
27244}
27245impl MessageData for SET_POSITION_TARGET_GLOBAL_INT_DATA {
27246 type Message = MavMessage;
27247 const ID: u32 = 86u32;
27248 const NAME: &'static str = "SET_POSITION_TARGET_GLOBAL_INT";
27249 const EXTRA_CRC: u8 = 5u8;
27250 const ENCODED_LEN: usize = 53usize;
27251 fn deser(
27252 _version: MavlinkVersion,
27253 __input: &[u8],
27254 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27255 let avail_len = __input.len();
27256 let mut payload_buf = [0; Self::ENCODED_LEN];
27257 let mut buf = if avail_len < Self::ENCODED_LEN {
27258 payload_buf[0..avail_len].copy_from_slice(__input);
27259 Bytes::new(&payload_buf)
27260 } else {
27261 Bytes::new(__input)
27262 };
27263 let mut __struct = Self::default();
27264 __struct.time_boot_ms = buf.get_u32_le();
27265 __struct.lat_int = buf.get_i32_le();
27266 __struct.lon_int = buf.get_i32_le();
27267 __struct.alt = buf.get_f32_le();
27268 __struct.vx = buf.get_f32_le();
27269 __struct.vy = buf.get_f32_le();
27270 __struct.vz = buf.get_f32_le();
27271 __struct.afx = buf.get_f32_le();
27272 __struct.afy = buf.get_f32_le();
27273 __struct.afz = buf.get_f32_le();
27274 __struct.yaw = buf.get_f32_le();
27275 __struct.yaw_rate = buf.get_f32_le();
27276 let tmp = buf.get_u16_le();
27277 __struct.type_mask = PositionTargetTypemask::from_bits(
27278 tmp & PositionTargetTypemask::all().bits(),
27279 )
27280 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
27281 flag_type: "PositionTargetTypemask",
27282 value: tmp as u32,
27283 })?;
27284 __struct.target_system = buf.get_u8();
27285 __struct.target_component = buf.get_u8();
27286 let tmp = buf.get_u8();
27287 __struct.coordinate_frame =
27288 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
27289 enum_type: "MavFrame",
27290 value: tmp as u32,
27291 })?;
27292 Ok(__struct)
27293 }
27294 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27295 let mut __tmp = BytesMut::new(bytes);
27296 #[allow(clippy::absurd_extreme_comparisons)]
27297 #[allow(unused_comparisons)]
27298 if __tmp.remaining() < Self::ENCODED_LEN {
27299 panic!(
27300 "buffer is too small (need {} bytes, but got {})",
27301 Self::ENCODED_LEN,
27302 __tmp.remaining(),
27303 )
27304 }
27305 __tmp.put_u32_le(self.time_boot_ms);
27306 __tmp.put_i32_le(self.lat_int);
27307 __tmp.put_i32_le(self.lon_int);
27308 __tmp.put_f32_le(self.alt);
27309 __tmp.put_f32_le(self.vx);
27310 __tmp.put_f32_le(self.vy);
27311 __tmp.put_f32_le(self.vz);
27312 __tmp.put_f32_le(self.afx);
27313 __tmp.put_f32_le(self.afy);
27314 __tmp.put_f32_le(self.afz);
27315 __tmp.put_f32_le(self.yaw);
27316 __tmp.put_f32_le(self.yaw_rate);
27317 __tmp.put_u16_le(self.type_mask.bits());
27318 __tmp.put_u8(self.target_system);
27319 __tmp.put_u8(self.target_component);
27320 __tmp.put_u8(self.coordinate_frame as u8);
27321 if matches!(version, MavlinkVersion::V2) {
27322 let len = __tmp.len();
27323 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27324 } else {
27325 __tmp.len()
27326 }
27327 }
27328}
27329#[doc = "id: 84"]
27330#[doc = "Sets a desired vehicle position in a local north-east-down coordinate frame. Used by an external controller to command the vehicle (manual controller or other system)."]
27331#[derive(Debug, Clone, PartialEq)]
27332#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27333#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27334pub struct SET_POSITION_TARGET_LOCAL_NED_DATA {
27335 #[doc = "Timestamp (time since system boot)."]
27336 pub time_boot_ms: u32,
27337 #[doc = "X Position in NED frame"]
27338 pub x: f32,
27339 #[doc = "Y Position in NED frame"]
27340 pub y: f32,
27341 #[doc = "Z Position in NED frame (note, altitude is negative in NED)"]
27342 pub z: f32,
27343 #[doc = "X velocity in NED frame"]
27344 pub vx: f32,
27345 #[doc = "Y velocity in NED frame"]
27346 pub vy: f32,
27347 #[doc = "Z velocity in NED frame"]
27348 pub vz: f32,
27349 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
27350 pub afx: f32,
27351 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
27352 pub afy: f32,
27353 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
27354 pub afz: f32,
27355 #[doc = "yaw setpoint"]
27356 pub yaw: f32,
27357 #[doc = "yaw rate setpoint"]
27358 pub yaw_rate: f32,
27359 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
27360 pub type_mask: PositionTargetTypemask,
27361 #[doc = "System ID"]
27362 pub target_system: u8,
27363 #[doc = "Component ID"]
27364 pub target_component: u8,
27365 #[doc = "Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9"]
27366 pub coordinate_frame: MavFrame,
27367}
27368impl SET_POSITION_TARGET_LOCAL_NED_DATA {
27369 pub const ENCODED_LEN: usize = 53usize;
27370 pub const DEFAULT: Self = Self {
27371 time_boot_ms: 0_u32,
27372 x: 0.0_f32,
27373 y: 0.0_f32,
27374 z: 0.0_f32,
27375 vx: 0.0_f32,
27376 vy: 0.0_f32,
27377 vz: 0.0_f32,
27378 afx: 0.0_f32,
27379 afy: 0.0_f32,
27380 afz: 0.0_f32,
27381 yaw: 0.0_f32,
27382 yaw_rate: 0.0_f32,
27383 type_mask: PositionTargetTypemask::DEFAULT,
27384 target_system: 0_u8,
27385 target_component: 0_u8,
27386 coordinate_frame: MavFrame::DEFAULT,
27387 };
27388 #[cfg(feature = "arbitrary")]
27389 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27390 use arbitrary::{Arbitrary, Unstructured};
27391 let mut buf = [0u8; 1024];
27392 rng.fill_bytes(&mut buf);
27393 let mut unstructured = Unstructured::new(&buf);
27394 Self::arbitrary(&mut unstructured).unwrap_or_default()
27395 }
27396}
27397impl Default for SET_POSITION_TARGET_LOCAL_NED_DATA {
27398 fn default() -> Self {
27399 Self::DEFAULT.clone()
27400 }
27401}
27402impl MessageData for SET_POSITION_TARGET_LOCAL_NED_DATA {
27403 type Message = MavMessage;
27404 const ID: u32 = 84u32;
27405 const NAME: &'static str = "SET_POSITION_TARGET_LOCAL_NED";
27406 const EXTRA_CRC: u8 = 143u8;
27407 const ENCODED_LEN: usize = 53usize;
27408 fn deser(
27409 _version: MavlinkVersion,
27410 __input: &[u8],
27411 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27412 let avail_len = __input.len();
27413 let mut payload_buf = [0; Self::ENCODED_LEN];
27414 let mut buf = if avail_len < Self::ENCODED_LEN {
27415 payload_buf[0..avail_len].copy_from_slice(__input);
27416 Bytes::new(&payload_buf)
27417 } else {
27418 Bytes::new(__input)
27419 };
27420 let mut __struct = Self::default();
27421 __struct.time_boot_ms = buf.get_u32_le();
27422 __struct.x = buf.get_f32_le();
27423 __struct.y = buf.get_f32_le();
27424 __struct.z = buf.get_f32_le();
27425 __struct.vx = buf.get_f32_le();
27426 __struct.vy = buf.get_f32_le();
27427 __struct.vz = buf.get_f32_le();
27428 __struct.afx = buf.get_f32_le();
27429 __struct.afy = buf.get_f32_le();
27430 __struct.afz = buf.get_f32_le();
27431 __struct.yaw = buf.get_f32_le();
27432 __struct.yaw_rate = buf.get_f32_le();
27433 let tmp = buf.get_u16_le();
27434 __struct.type_mask = PositionTargetTypemask::from_bits(
27435 tmp & PositionTargetTypemask::all().bits(),
27436 )
27437 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
27438 flag_type: "PositionTargetTypemask",
27439 value: tmp as u32,
27440 })?;
27441 __struct.target_system = buf.get_u8();
27442 __struct.target_component = buf.get_u8();
27443 let tmp = buf.get_u8();
27444 __struct.coordinate_frame =
27445 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
27446 enum_type: "MavFrame",
27447 value: tmp as u32,
27448 })?;
27449 Ok(__struct)
27450 }
27451 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27452 let mut __tmp = BytesMut::new(bytes);
27453 #[allow(clippy::absurd_extreme_comparisons)]
27454 #[allow(unused_comparisons)]
27455 if __tmp.remaining() < Self::ENCODED_LEN {
27456 panic!(
27457 "buffer is too small (need {} bytes, but got {})",
27458 Self::ENCODED_LEN,
27459 __tmp.remaining(),
27460 )
27461 }
27462 __tmp.put_u32_le(self.time_boot_ms);
27463 __tmp.put_f32_le(self.x);
27464 __tmp.put_f32_le(self.y);
27465 __tmp.put_f32_le(self.z);
27466 __tmp.put_f32_le(self.vx);
27467 __tmp.put_f32_le(self.vy);
27468 __tmp.put_f32_le(self.vz);
27469 __tmp.put_f32_le(self.afx);
27470 __tmp.put_f32_le(self.afy);
27471 __tmp.put_f32_le(self.afz);
27472 __tmp.put_f32_le(self.yaw);
27473 __tmp.put_f32_le(self.yaw_rate);
27474 __tmp.put_u16_le(self.type_mask.bits());
27475 __tmp.put_u8(self.target_system);
27476 __tmp.put_u8(self.target_component);
27477 __tmp.put_u8(self.coordinate_frame as u8);
27478 if matches!(version, MavlinkVersion::V2) {
27479 let len = __tmp.len();
27480 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27481 } else {
27482 __tmp.len()
27483 }
27484 }
27485}
27486#[doc = "id: 108"]
27487#[doc = "Status of simulation environment, if used."]
27488#[derive(Debug, Clone, PartialEq)]
27489#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27490#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27491pub struct SIM_STATE_DATA {
27492 #[doc = "True attitude quaternion component 1, w (1 in null-rotation)"]
27493 pub q1: f32,
27494 #[doc = "True attitude quaternion component 2, x (0 in null-rotation)"]
27495 pub q2: f32,
27496 #[doc = "True attitude quaternion component 3, y (0 in null-rotation)"]
27497 pub q3: f32,
27498 #[doc = "True attitude quaternion component 4, z (0 in null-rotation)"]
27499 pub q4: f32,
27500 #[doc = "Attitude roll expressed as Euler angles, not recommended except for human-readable outputs"]
27501 pub roll: f32,
27502 #[doc = "Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs"]
27503 pub pitch: f32,
27504 #[doc = "Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs"]
27505 pub yaw: f32,
27506 #[doc = "X acceleration"]
27507 pub xacc: f32,
27508 #[doc = "Y acceleration"]
27509 pub yacc: f32,
27510 #[doc = "Z acceleration"]
27511 pub zacc: f32,
27512 #[doc = "Angular speed around X axis"]
27513 pub xgyro: f32,
27514 #[doc = "Angular speed around Y axis"]
27515 pub ygyro: f32,
27516 #[doc = "Angular speed around Z axis"]
27517 pub zgyro: f32,
27518 #[doc = "Latitude (lower precision). Both this and the lat_int field should be set."]
27519 pub lat: f32,
27520 #[doc = "Longitude (lower precision). Both this and the lon_int field should be set."]
27521 pub lon: f32,
27522 #[doc = "Altitude"]
27523 pub alt: f32,
27524 #[doc = "Horizontal position standard deviation"]
27525 pub std_dev_horz: f32,
27526 #[doc = "Vertical position standard deviation"]
27527 pub std_dev_vert: f32,
27528 #[doc = "True velocity in north direction in earth-fixed NED frame"]
27529 pub vn: f32,
27530 #[doc = "True velocity in east direction in earth-fixed NED frame"]
27531 pub ve: f32,
27532 #[doc = "True velocity in down direction in earth-fixed NED frame"]
27533 pub vd: f32,
27534 #[doc = "Latitude (higher precision). If 0, recipients should use the lat field value (otherwise this field is preferred)."]
27535 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27536 pub lat_int: i32,
27537 #[doc = "Longitude (higher precision). If 0, recipients should use the lon field value (otherwise this field is preferred)."]
27538 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27539 pub lon_int: i32,
27540}
27541impl SIM_STATE_DATA {
27542 pub const ENCODED_LEN: usize = 92usize;
27543 pub const DEFAULT: Self = Self {
27544 q1: 0.0_f32,
27545 q2: 0.0_f32,
27546 q3: 0.0_f32,
27547 q4: 0.0_f32,
27548 roll: 0.0_f32,
27549 pitch: 0.0_f32,
27550 yaw: 0.0_f32,
27551 xacc: 0.0_f32,
27552 yacc: 0.0_f32,
27553 zacc: 0.0_f32,
27554 xgyro: 0.0_f32,
27555 ygyro: 0.0_f32,
27556 zgyro: 0.0_f32,
27557 lat: 0.0_f32,
27558 lon: 0.0_f32,
27559 alt: 0.0_f32,
27560 std_dev_horz: 0.0_f32,
27561 std_dev_vert: 0.0_f32,
27562 vn: 0.0_f32,
27563 ve: 0.0_f32,
27564 vd: 0.0_f32,
27565 lat_int: 0_i32,
27566 lon_int: 0_i32,
27567 };
27568 #[cfg(feature = "arbitrary")]
27569 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27570 use arbitrary::{Arbitrary, Unstructured};
27571 let mut buf = [0u8; 1024];
27572 rng.fill_bytes(&mut buf);
27573 let mut unstructured = Unstructured::new(&buf);
27574 Self::arbitrary(&mut unstructured).unwrap_or_default()
27575 }
27576}
27577impl Default for SIM_STATE_DATA {
27578 fn default() -> Self {
27579 Self::DEFAULT.clone()
27580 }
27581}
27582impl MessageData for SIM_STATE_DATA {
27583 type Message = MavMessage;
27584 const ID: u32 = 108u32;
27585 const NAME: &'static str = "SIM_STATE";
27586 const EXTRA_CRC: u8 = 32u8;
27587 const ENCODED_LEN: usize = 92usize;
27588 fn deser(
27589 _version: MavlinkVersion,
27590 __input: &[u8],
27591 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27592 let avail_len = __input.len();
27593 let mut payload_buf = [0; Self::ENCODED_LEN];
27594 let mut buf = if avail_len < Self::ENCODED_LEN {
27595 payload_buf[0..avail_len].copy_from_slice(__input);
27596 Bytes::new(&payload_buf)
27597 } else {
27598 Bytes::new(__input)
27599 };
27600 let mut __struct = Self::default();
27601 __struct.q1 = buf.get_f32_le();
27602 __struct.q2 = buf.get_f32_le();
27603 __struct.q3 = buf.get_f32_le();
27604 __struct.q4 = buf.get_f32_le();
27605 __struct.roll = buf.get_f32_le();
27606 __struct.pitch = buf.get_f32_le();
27607 __struct.yaw = buf.get_f32_le();
27608 __struct.xacc = buf.get_f32_le();
27609 __struct.yacc = buf.get_f32_le();
27610 __struct.zacc = buf.get_f32_le();
27611 __struct.xgyro = buf.get_f32_le();
27612 __struct.ygyro = buf.get_f32_le();
27613 __struct.zgyro = buf.get_f32_le();
27614 __struct.lat = buf.get_f32_le();
27615 __struct.lon = buf.get_f32_le();
27616 __struct.alt = buf.get_f32_le();
27617 __struct.std_dev_horz = buf.get_f32_le();
27618 __struct.std_dev_vert = buf.get_f32_le();
27619 __struct.vn = buf.get_f32_le();
27620 __struct.ve = buf.get_f32_le();
27621 __struct.vd = buf.get_f32_le();
27622 __struct.lat_int = buf.get_i32_le();
27623 __struct.lon_int = buf.get_i32_le();
27624 Ok(__struct)
27625 }
27626 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27627 let mut __tmp = BytesMut::new(bytes);
27628 #[allow(clippy::absurd_extreme_comparisons)]
27629 #[allow(unused_comparisons)]
27630 if __tmp.remaining() < Self::ENCODED_LEN {
27631 panic!(
27632 "buffer is too small (need {} bytes, but got {})",
27633 Self::ENCODED_LEN,
27634 __tmp.remaining(),
27635 )
27636 }
27637 __tmp.put_f32_le(self.q1);
27638 __tmp.put_f32_le(self.q2);
27639 __tmp.put_f32_le(self.q3);
27640 __tmp.put_f32_le(self.q4);
27641 __tmp.put_f32_le(self.roll);
27642 __tmp.put_f32_le(self.pitch);
27643 __tmp.put_f32_le(self.yaw);
27644 __tmp.put_f32_le(self.xacc);
27645 __tmp.put_f32_le(self.yacc);
27646 __tmp.put_f32_le(self.zacc);
27647 __tmp.put_f32_le(self.xgyro);
27648 __tmp.put_f32_le(self.ygyro);
27649 __tmp.put_f32_le(self.zgyro);
27650 __tmp.put_f32_le(self.lat);
27651 __tmp.put_f32_le(self.lon);
27652 __tmp.put_f32_le(self.alt);
27653 __tmp.put_f32_le(self.std_dev_horz);
27654 __tmp.put_f32_le(self.std_dev_vert);
27655 __tmp.put_f32_le(self.vn);
27656 __tmp.put_f32_le(self.ve);
27657 __tmp.put_f32_le(self.vd);
27658 __tmp.put_i32_le(self.lat_int);
27659 __tmp.put_i32_le(self.lon_int);
27660 if matches!(version, MavlinkVersion::V2) {
27661 let len = __tmp.len();
27662 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27663 } else {
27664 __tmp.len()
27665 }
27666 }
27667}
27668#[doc = "id: 370"]
27669#[doc = "Smart Battery information (static/infrequent update). Use for updates from: smart battery to flight stack, flight stack to GCS. Use BATTERY_STATUS for the frequent battery updates."]
27670#[derive(Debug, Clone, PartialEq)]
27671#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27672#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27673pub struct SMART_BATTERY_INFO_DATA {
27674 #[doc = "Capacity when full according to manufacturer, -1: field not provided."]
27675 pub capacity_full_specification: i32,
27676 #[doc = "Capacity when full (accounting for battery degradation), -1: field not provided."]
27677 pub capacity_full: i32,
27678 #[doc = "Charge/discharge cycle count. UINT16_MAX: field not provided."]
27679 pub cycle_count: u16,
27680 #[doc = "Battery weight. 0: field not provided."]
27681 pub weight: u16,
27682 #[doc = "Minimum per-cell voltage when discharging. If not supplied set to UINT16_MAX value."]
27683 pub discharge_minimum_voltage: u16,
27684 #[doc = "Minimum per-cell voltage when charging. If not supplied set to UINT16_MAX value."]
27685 pub charging_minimum_voltage: u16,
27686 #[doc = "Minimum per-cell voltage when resting. If not supplied set to UINT16_MAX value."]
27687 pub resting_minimum_voltage: u16,
27688 #[doc = "Battery ID"]
27689 pub id: u8,
27690 #[doc = "Function of the battery"]
27691 pub battery_function: MavBatteryFunction,
27692 #[doc = "Type (chemistry) of the battery"]
27693 pub mavtype: MavBatteryType,
27694 #[doc = "Serial number in ASCII characters, 0 terminated. All 0: field not provided."]
27695 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27696 pub serial_number: [u8; 16],
27697 #[doc = "Static device name in ASCII characters, 0 terminated. All 0: field not provided. Encode as manufacturer name then product name separated using an underscore."]
27698 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27699 pub device_name: [u8; 50],
27700 #[doc = "Maximum per-cell voltage when charged. 0: field not provided."]
27701 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27702 pub charging_maximum_voltage: u16,
27703 #[doc = "Number of battery cells in series. 0: field not provided."]
27704 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27705 pub cells_in_series: u8,
27706 #[doc = "Maximum pack discharge current. 0: field not provided."]
27707 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27708 pub discharge_maximum_current: u32,
27709 #[doc = "Maximum pack discharge burst current. 0: field not provided."]
27710 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27711 pub discharge_maximum_burst_current: u32,
27712 #[doc = "Manufacture date (DD/MM/YYYY) in ASCII characters, 0 terminated. All 0: field not provided."]
27713 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27714 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27715 pub manufacture_date: [u8; 11],
27716}
27717impl SMART_BATTERY_INFO_DATA {
27718 pub const ENCODED_LEN: usize = 109usize;
27719 pub const DEFAULT: Self = Self {
27720 capacity_full_specification: 0_i32,
27721 capacity_full: 0_i32,
27722 cycle_count: 0_u16,
27723 weight: 0_u16,
27724 discharge_minimum_voltage: 0_u16,
27725 charging_minimum_voltage: 0_u16,
27726 resting_minimum_voltage: 0_u16,
27727 id: 0_u8,
27728 battery_function: MavBatteryFunction::DEFAULT,
27729 mavtype: MavBatteryType::DEFAULT,
27730 serial_number: [0_u8; 16usize],
27731 device_name: [0_u8; 50usize],
27732 charging_maximum_voltage: 0_u16,
27733 cells_in_series: 0_u8,
27734 discharge_maximum_current: 0_u32,
27735 discharge_maximum_burst_current: 0_u32,
27736 manufacture_date: [0_u8; 11usize],
27737 };
27738 #[cfg(feature = "arbitrary")]
27739 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27740 use arbitrary::{Arbitrary, Unstructured};
27741 let mut buf = [0u8; 1024];
27742 rng.fill_bytes(&mut buf);
27743 let mut unstructured = Unstructured::new(&buf);
27744 Self::arbitrary(&mut unstructured).unwrap_or_default()
27745 }
27746}
27747impl Default for SMART_BATTERY_INFO_DATA {
27748 fn default() -> Self {
27749 Self::DEFAULT.clone()
27750 }
27751}
27752impl MessageData for SMART_BATTERY_INFO_DATA {
27753 type Message = MavMessage;
27754 const ID: u32 = 370u32;
27755 const NAME: &'static str = "SMART_BATTERY_INFO";
27756 const EXTRA_CRC: u8 = 75u8;
27757 const ENCODED_LEN: usize = 109usize;
27758 fn deser(
27759 _version: MavlinkVersion,
27760 __input: &[u8],
27761 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27762 let avail_len = __input.len();
27763 let mut payload_buf = [0; Self::ENCODED_LEN];
27764 let mut buf = if avail_len < Self::ENCODED_LEN {
27765 payload_buf[0..avail_len].copy_from_slice(__input);
27766 Bytes::new(&payload_buf)
27767 } else {
27768 Bytes::new(__input)
27769 };
27770 let mut __struct = Self::default();
27771 __struct.capacity_full_specification = buf.get_i32_le();
27772 __struct.capacity_full = buf.get_i32_le();
27773 __struct.cycle_count = buf.get_u16_le();
27774 __struct.weight = buf.get_u16_le();
27775 __struct.discharge_minimum_voltage = buf.get_u16_le();
27776 __struct.charging_minimum_voltage = buf.get_u16_le();
27777 __struct.resting_minimum_voltage = buf.get_u16_le();
27778 __struct.id = buf.get_u8();
27779 let tmp = buf.get_u8();
27780 __struct.battery_function =
27781 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
27782 enum_type: "MavBatteryFunction",
27783 value: tmp as u32,
27784 })?;
27785 let tmp = buf.get_u8();
27786 __struct.mavtype =
27787 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
27788 enum_type: "MavBatteryType",
27789 value: tmp as u32,
27790 })?;
27791 for v in &mut __struct.serial_number {
27792 let val = buf.get_u8();
27793 *v = val;
27794 }
27795 for v in &mut __struct.device_name {
27796 let val = buf.get_u8();
27797 *v = val;
27798 }
27799 __struct.charging_maximum_voltage = buf.get_u16_le();
27800 __struct.cells_in_series = buf.get_u8();
27801 __struct.discharge_maximum_current = buf.get_u32_le();
27802 __struct.discharge_maximum_burst_current = buf.get_u32_le();
27803 for v in &mut __struct.manufacture_date {
27804 let val = buf.get_u8();
27805 *v = val;
27806 }
27807 Ok(__struct)
27808 }
27809 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27810 let mut __tmp = BytesMut::new(bytes);
27811 #[allow(clippy::absurd_extreme_comparisons)]
27812 #[allow(unused_comparisons)]
27813 if __tmp.remaining() < Self::ENCODED_LEN {
27814 panic!(
27815 "buffer is too small (need {} bytes, but got {})",
27816 Self::ENCODED_LEN,
27817 __tmp.remaining(),
27818 )
27819 }
27820 __tmp.put_i32_le(self.capacity_full_specification);
27821 __tmp.put_i32_le(self.capacity_full);
27822 __tmp.put_u16_le(self.cycle_count);
27823 __tmp.put_u16_le(self.weight);
27824 __tmp.put_u16_le(self.discharge_minimum_voltage);
27825 __tmp.put_u16_le(self.charging_minimum_voltage);
27826 __tmp.put_u16_le(self.resting_minimum_voltage);
27827 __tmp.put_u8(self.id);
27828 __tmp.put_u8(self.battery_function as u8);
27829 __tmp.put_u8(self.mavtype as u8);
27830 for val in &self.serial_number {
27831 __tmp.put_u8(*val);
27832 }
27833 for val in &self.device_name {
27834 __tmp.put_u8(*val);
27835 }
27836 __tmp.put_u16_le(self.charging_maximum_voltage);
27837 __tmp.put_u8(self.cells_in_series);
27838 __tmp.put_u32_le(self.discharge_maximum_current);
27839 __tmp.put_u32_le(self.discharge_maximum_burst_current);
27840 for val in &self.manufacture_date {
27841 __tmp.put_u8(*val);
27842 }
27843 if matches!(version, MavlinkVersion::V2) {
27844 let len = __tmp.len();
27845 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27846 } else {
27847 __tmp.len()
27848 }
27849 }
27850}
27851#[doc = "id: 253"]
27852#[doc = "Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz)."]
27853#[derive(Debug, Clone, PartialEq)]
27854#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27855#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27856pub struct STATUSTEXT_DATA {
27857 #[doc = "Severity of status. Relies on the definitions within RFC-5424."]
27858 pub severity: MavSeverity,
27859 #[doc = "Status text message, without null termination character"]
27860 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27861 pub text: [u8; 50],
27862 #[doc = "Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately."]
27863 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27864 pub id: u16,
27865 #[doc = "This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk."]
27866 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27867 pub chunk_seq: u8,
27868}
27869impl STATUSTEXT_DATA {
27870 pub const ENCODED_LEN: usize = 54usize;
27871 pub const DEFAULT: Self = Self {
27872 severity: MavSeverity::DEFAULT,
27873 text: [0_u8; 50usize],
27874 id: 0_u16,
27875 chunk_seq: 0_u8,
27876 };
27877 #[cfg(feature = "arbitrary")]
27878 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27879 use arbitrary::{Arbitrary, Unstructured};
27880 let mut buf = [0u8; 1024];
27881 rng.fill_bytes(&mut buf);
27882 let mut unstructured = Unstructured::new(&buf);
27883 Self::arbitrary(&mut unstructured).unwrap_or_default()
27884 }
27885}
27886impl Default for STATUSTEXT_DATA {
27887 fn default() -> Self {
27888 Self::DEFAULT.clone()
27889 }
27890}
27891impl MessageData for STATUSTEXT_DATA {
27892 type Message = MavMessage;
27893 const ID: u32 = 253u32;
27894 const NAME: &'static str = "STATUSTEXT";
27895 const EXTRA_CRC: u8 = 83u8;
27896 const ENCODED_LEN: usize = 54usize;
27897 fn deser(
27898 _version: MavlinkVersion,
27899 __input: &[u8],
27900 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27901 let avail_len = __input.len();
27902 let mut payload_buf = [0; Self::ENCODED_LEN];
27903 let mut buf = if avail_len < Self::ENCODED_LEN {
27904 payload_buf[0..avail_len].copy_from_slice(__input);
27905 Bytes::new(&payload_buf)
27906 } else {
27907 Bytes::new(__input)
27908 };
27909 let mut __struct = Self::default();
27910 let tmp = buf.get_u8();
27911 __struct.severity =
27912 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
27913 enum_type: "MavSeverity",
27914 value: tmp as u32,
27915 })?;
27916 for v in &mut __struct.text {
27917 let val = buf.get_u8();
27918 *v = val;
27919 }
27920 __struct.id = buf.get_u16_le();
27921 __struct.chunk_seq = buf.get_u8();
27922 Ok(__struct)
27923 }
27924 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27925 let mut __tmp = BytesMut::new(bytes);
27926 #[allow(clippy::absurd_extreme_comparisons)]
27927 #[allow(unused_comparisons)]
27928 if __tmp.remaining() < Self::ENCODED_LEN {
27929 panic!(
27930 "buffer is too small (need {} bytes, but got {})",
27931 Self::ENCODED_LEN,
27932 __tmp.remaining(),
27933 )
27934 }
27935 __tmp.put_u8(self.severity as u8);
27936 for val in &self.text {
27937 __tmp.put_u8(*val);
27938 }
27939 __tmp.put_u16_le(self.id);
27940 __tmp.put_u8(self.chunk_seq);
27941 if matches!(version, MavlinkVersion::V2) {
27942 let len = __tmp.len();
27943 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27944 } else {
27945 __tmp.len()
27946 }
27947 }
27948}
27949#[doc = "id: 261"]
27950#[doc = "Information about a storage medium. This message is sent in response to a request with MAV_CMD_REQUEST_MESSAGE and whenever the status of the storage changes (STORAGE_STATUS). Use MAV_CMD_REQUEST_MESSAGE.param2 to indicate the index/id of requested storage: 0 for all, 1 for first, 2 for second, etc."]
27951#[derive(Debug, Clone, PartialEq)]
27952#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27953#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27954pub struct STORAGE_INFORMATION_DATA {
27955 #[doc = "Timestamp (time since system boot)."]
27956 pub time_boot_ms: u32,
27957 #[doc = "Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored."]
27958 pub total_capacity: f32,
27959 #[doc = "Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored."]
27960 pub used_capacity: f32,
27961 #[doc = "Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored."]
27962 pub available_capacity: f32,
27963 #[doc = "Read speed."]
27964 pub read_speed: f32,
27965 #[doc = "Write speed."]
27966 pub write_speed: f32,
27967 #[doc = "Storage ID (1 for first, 2 for second, etc.)"]
27968 pub storage_id: u8,
27969 #[doc = "Number of storage devices"]
27970 pub storage_count: u8,
27971 #[doc = "Status of storage"]
27972 pub status: StorageStatus,
27973 #[doc = "Type of storage"]
27974 #[cfg_attr(feature = "serde", serde(default))]
27975 pub mavtype: StorageType,
27976 #[doc = "Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user."]
27977 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27978 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27979 pub name: [u8; 32],
27980 #[doc = "Flags indicating whether this instance is preferred storage for photos, videos, etc. Note: Implementations should initially set the flags on the system-default storage id used for saving media (if possible/supported). This setting can then be overridden using MAV_CMD_SET_STORAGE_USAGE. If the media usage flags are not set, a GCS may assume storage ID 1 is the default storage for all media types."]
27981 #[cfg_attr(feature = "serde", serde(default))]
27982 pub storage_usage: StorageUsageFlag,
27983}
27984impl STORAGE_INFORMATION_DATA {
27985 pub const ENCODED_LEN: usize = 61usize;
27986 pub const DEFAULT: Self = Self {
27987 time_boot_ms: 0_u32,
27988 total_capacity: 0.0_f32,
27989 used_capacity: 0.0_f32,
27990 available_capacity: 0.0_f32,
27991 read_speed: 0.0_f32,
27992 write_speed: 0.0_f32,
27993 storage_id: 0_u8,
27994 storage_count: 0_u8,
27995 status: StorageStatus::DEFAULT,
27996 mavtype: StorageType::DEFAULT,
27997 name: [0_u8; 32usize],
27998 storage_usage: StorageUsageFlag::DEFAULT,
27999 };
28000 #[cfg(feature = "arbitrary")]
28001 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28002 use arbitrary::{Arbitrary, Unstructured};
28003 let mut buf = [0u8; 1024];
28004 rng.fill_bytes(&mut buf);
28005 let mut unstructured = Unstructured::new(&buf);
28006 Self::arbitrary(&mut unstructured).unwrap_or_default()
28007 }
28008}
28009impl Default for STORAGE_INFORMATION_DATA {
28010 fn default() -> Self {
28011 Self::DEFAULT.clone()
28012 }
28013}
28014impl MessageData for STORAGE_INFORMATION_DATA {
28015 type Message = MavMessage;
28016 const ID: u32 = 261u32;
28017 const NAME: &'static str = "STORAGE_INFORMATION";
28018 const EXTRA_CRC: u8 = 179u8;
28019 const ENCODED_LEN: usize = 61usize;
28020 fn deser(
28021 _version: MavlinkVersion,
28022 __input: &[u8],
28023 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28024 let avail_len = __input.len();
28025 let mut payload_buf = [0; Self::ENCODED_LEN];
28026 let mut buf = if avail_len < Self::ENCODED_LEN {
28027 payload_buf[0..avail_len].copy_from_slice(__input);
28028 Bytes::new(&payload_buf)
28029 } else {
28030 Bytes::new(__input)
28031 };
28032 let mut __struct = Self::default();
28033 __struct.time_boot_ms = buf.get_u32_le();
28034 __struct.total_capacity = buf.get_f32_le();
28035 __struct.used_capacity = buf.get_f32_le();
28036 __struct.available_capacity = buf.get_f32_le();
28037 __struct.read_speed = buf.get_f32_le();
28038 __struct.write_speed = buf.get_f32_le();
28039 __struct.storage_id = buf.get_u8();
28040 __struct.storage_count = buf.get_u8();
28041 let tmp = buf.get_u8();
28042 __struct.status =
28043 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
28044 enum_type: "StorageStatus",
28045 value: tmp as u32,
28046 })?;
28047 let tmp = buf.get_u8();
28048 __struct.mavtype =
28049 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
28050 enum_type: "StorageType",
28051 value: tmp as u32,
28052 })?;
28053 for v in &mut __struct.name {
28054 let val = buf.get_u8();
28055 *v = val;
28056 }
28057 let tmp = buf.get_u8();
28058 __struct.storage_usage = StorageUsageFlag::from_bits(tmp & StorageUsageFlag::all().bits())
28059 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
28060 flag_type: "StorageUsageFlag",
28061 value: tmp as u32,
28062 })?;
28063 Ok(__struct)
28064 }
28065 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28066 let mut __tmp = BytesMut::new(bytes);
28067 #[allow(clippy::absurd_extreme_comparisons)]
28068 #[allow(unused_comparisons)]
28069 if __tmp.remaining() < Self::ENCODED_LEN {
28070 panic!(
28071 "buffer is too small (need {} bytes, but got {})",
28072 Self::ENCODED_LEN,
28073 __tmp.remaining(),
28074 )
28075 }
28076 __tmp.put_u32_le(self.time_boot_ms);
28077 __tmp.put_f32_le(self.total_capacity);
28078 __tmp.put_f32_le(self.used_capacity);
28079 __tmp.put_f32_le(self.available_capacity);
28080 __tmp.put_f32_le(self.read_speed);
28081 __tmp.put_f32_le(self.write_speed);
28082 __tmp.put_u8(self.storage_id);
28083 __tmp.put_u8(self.storage_count);
28084 __tmp.put_u8(self.status as u8);
28085 __tmp.put_u8(self.mavtype as u8);
28086 for val in &self.name {
28087 __tmp.put_u8(*val);
28088 }
28089 __tmp.put_u8(self.storage_usage.bits());
28090 if matches!(version, MavlinkVersion::V2) {
28091 let len = __tmp.len();
28092 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28093 } else {
28094 __tmp.len()
28095 }
28096 }
28097}
28098#[doc = "id: 401"]
28099#[doc = "Tune formats supported by vehicle. This should be emitted as response to MAV_CMD_REQUEST_MESSAGE."]
28100#[derive(Debug, Clone, PartialEq)]
28101#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28102#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28103pub struct SUPPORTED_TUNES_DATA {
28104 #[doc = "Bitfield of supported tune formats."]
28105 pub format: TuneFormat,
28106 #[doc = "System ID"]
28107 pub target_system: u8,
28108 #[doc = "Component ID"]
28109 pub target_component: u8,
28110}
28111impl SUPPORTED_TUNES_DATA {
28112 pub const ENCODED_LEN: usize = 6usize;
28113 pub const DEFAULT: Self = Self {
28114 format: TuneFormat::DEFAULT,
28115 target_system: 0_u8,
28116 target_component: 0_u8,
28117 };
28118 #[cfg(feature = "arbitrary")]
28119 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28120 use arbitrary::{Arbitrary, Unstructured};
28121 let mut buf = [0u8; 1024];
28122 rng.fill_bytes(&mut buf);
28123 let mut unstructured = Unstructured::new(&buf);
28124 Self::arbitrary(&mut unstructured).unwrap_or_default()
28125 }
28126}
28127impl Default for SUPPORTED_TUNES_DATA {
28128 fn default() -> Self {
28129 Self::DEFAULT.clone()
28130 }
28131}
28132impl MessageData for SUPPORTED_TUNES_DATA {
28133 type Message = MavMessage;
28134 const ID: u32 = 401u32;
28135 const NAME: &'static str = "SUPPORTED_TUNES";
28136 const EXTRA_CRC: u8 = 183u8;
28137 const ENCODED_LEN: usize = 6usize;
28138 fn deser(
28139 _version: MavlinkVersion,
28140 __input: &[u8],
28141 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28142 let avail_len = __input.len();
28143 let mut payload_buf = [0; Self::ENCODED_LEN];
28144 let mut buf = if avail_len < Self::ENCODED_LEN {
28145 payload_buf[0..avail_len].copy_from_slice(__input);
28146 Bytes::new(&payload_buf)
28147 } else {
28148 Bytes::new(__input)
28149 };
28150 let mut __struct = Self::default();
28151 let tmp = buf.get_u32_le();
28152 __struct.format = FromPrimitive::from_u32(tmp).ok_or(
28153 ::mavlink_core::error::ParserError::InvalidEnum {
28154 enum_type: "TuneFormat",
28155 value: tmp as u32,
28156 },
28157 )?;
28158 __struct.target_system = buf.get_u8();
28159 __struct.target_component = buf.get_u8();
28160 Ok(__struct)
28161 }
28162 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28163 let mut __tmp = BytesMut::new(bytes);
28164 #[allow(clippy::absurd_extreme_comparisons)]
28165 #[allow(unused_comparisons)]
28166 if __tmp.remaining() < Self::ENCODED_LEN {
28167 panic!(
28168 "buffer is too small (need {} bytes, but got {})",
28169 Self::ENCODED_LEN,
28170 __tmp.remaining(),
28171 )
28172 }
28173 __tmp.put_u32_le(self.format as u32);
28174 __tmp.put_u8(self.target_system);
28175 __tmp.put_u8(self.target_component);
28176 if matches!(version, MavlinkVersion::V2) {
28177 let len = __tmp.len();
28178 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28179 } else {
28180 __tmp.len()
28181 }
28182 }
28183}
28184#[doc = "id: 2"]
28185#[doc = "The system time is the time of the master clock. This can be emitted by flight controllers, onboard computers, or other components in the MAVLink network. Components that are using a less reliable time source, such as a battery-backed real time clock, can choose to match their system clock to that of a SYSTEM_TYPE that indicates a more recent time. This allows more broadly accurate date stamping of logs, and so on. If precise time synchronization is needed then use TIMESYNC instead."]
28186#[derive(Debug, Clone, PartialEq)]
28187#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28188#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28189pub struct SYSTEM_TIME_DATA {
28190 #[doc = "Timestamp (UNIX epoch time)."]
28191 pub time_unix_usec: u64,
28192 #[doc = "Timestamp (time since system boot)."]
28193 pub time_boot_ms: u32,
28194}
28195impl SYSTEM_TIME_DATA {
28196 pub const ENCODED_LEN: usize = 12usize;
28197 pub const DEFAULT: Self = Self {
28198 time_unix_usec: 0_u64,
28199 time_boot_ms: 0_u32,
28200 };
28201 #[cfg(feature = "arbitrary")]
28202 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28203 use arbitrary::{Arbitrary, Unstructured};
28204 let mut buf = [0u8; 1024];
28205 rng.fill_bytes(&mut buf);
28206 let mut unstructured = Unstructured::new(&buf);
28207 Self::arbitrary(&mut unstructured).unwrap_or_default()
28208 }
28209}
28210impl Default for SYSTEM_TIME_DATA {
28211 fn default() -> Self {
28212 Self::DEFAULT.clone()
28213 }
28214}
28215impl MessageData for SYSTEM_TIME_DATA {
28216 type Message = MavMessage;
28217 const ID: u32 = 2u32;
28218 const NAME: &'static str = "SYSTEM_TIME";
28219 const EXTRA_CRC: u8 = 137u8;
28220 const ENCODED_LEN: usize = 12usize;
28221 fn deser(
28222 _version: MavlinkVersion,
28223 __input: &[u8],
28224 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28225 let avail_len = __input.len();
28226 let mut payload_buf = [0; Self::ENCODED_LEN];
28227 let mut buf = if avail_len < Self::ENCODED_LEN {
28228 payload_buf[0..avail_len].copy_from_slice(__input);
28229 Bytes::new(&payload_buf)
28230 } else {
28231 Bytes::new(__input)
28232 };
28233 let mut __struct = Self::default();
28234 __struct.time_unix_usec = buf.get_u64_le();
28235 __struct.time_boot_ms = buf.get_u32_le();
28236 Ok(__struct)
28237 }
28238 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28239 let mut __tmp = BytesMut::new(bytes);
28240 #[allow(clippy::absurd_extreme_comparisons)]
28241 #[allow(unused_comparisons)]
28242 if __tmp.remaining() < Self::ENCODED_LEN {
28243 panic!(
28244 "buffer is too small (need {} bytes, but got {})",
28245 Self::ENCODED_LEN,
28246 __tmp.remaining(),
28247 )
28248 }
28249 __tmp.put_u64_le(self.time_unix_usec);
28250 __tmp.put_u32_le(self.time_boot_ms);
28251 if matches!(version, MavlinkVersion::V2) {
28252 let len = __tmp.len();
28253 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28254 } else {
28255 __tmp.len()
28256 }
28257 }
28258}
28259#[doc = "id: 1"]
28260#[doc = "The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows whether the system is currently active or not and if an emergency occurred. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occurred it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout."]
28261#[derive(Debug, Clone, PartialEq)]
28262#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28263#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28264pub struct SYS_STATUS_DATA {
28265 #[doc = "Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present."]
28266 pub onboard_control_sensors_present: MavSysStatusSensor,
28267 #[doc = "Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled."]
28268 pub onboard_control_sensors_enabled: MavSysStatusSensor,
28269 #[doc = "Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy."]
28270 pub onboard_control_sensors_health: MavSysStatusSensor,
28271 #[doc = "Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000"]
28272 pub load: u16,
28273 #[doc = "Battery voltage, UINT16_MAX: Voltage not sent by autopilot"]
28274 pub voltage_battery: u16,
28275 #[doc = "Battery current, -1: Current not sent by autopilot"]
28276 pub current_battery: i16,
28277 #[doc = "Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)"]
28278 pub drop_rate_comm: u16,
28279 #[doc = "Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)"]
28280 pub errors_comm: u16,
28281 #[doc = "Autopilot-specific errors"]
28282 pub errors_count1: u16,
28283 #[doc = "Autopilot-specific errors"]
28284 pub errors_count2: u16,
28285 #[doc = "Autopilot-specific errors"]
28286 pub errors_count3: u16,
28287 #[doc = "Autopilot-specific errors"]
28288 pub errors_count4: u16,
28289 #[doc = "Battery energy remaining, -1: Battery remaining energy not sent by autopilot"]
28290 pub battery_remaining: i8,
28291 #[doc = "Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present."]
28292 #[cfg_attr(feature = "serde", serde(default))]
28293 pub onboard_control_sensors_present_extended: MavSysStatusSensorExtended,
28294 #[doc = "Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled."]
28295 #[cfg_attr(feature = "serde", serde(default))]
28296 pub onboard_control_sensors_enabled_extended: MavSysStatusSensorExtended,
28297 #[doc = "Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy."]
28298 #[cfg_attr(feature = "serde", serde(default))]
28299 pub onboard_control_sensors_health_extended: MavSysStatusSensorExtended,
28300}
28301impl SYS_STATUS_DATA {
28302 pub const ENCODED_LEN: usize = 43usize;
28303 pub const DEFAULT: Self = Self {
28304 onboard_control_sensors_present: MavSysStatusSensor::DEFAULT,
28305 onboard_control_sensors_enabled: MavSysStatusSensor::DEFAULT,
28306 onboard_control_sensors_health: MavSysStatusSensor::DEFAULT,
28307 load: 0_u16,
28308 voltage_battery: 0_u16,
28309 current_battery: 0_i16,
28310 drop_rate_comm: 0_u16,
28311 errors_comm: 0_u16,
28312 errors_count1: 0_u16,
28313 errors_count2: 0_u16,
28314 errors_count3: 0_u16,
28315 errors_count4: 0_u16,
28316 battery_remaining: 0_i8,
28317 onboard_control_sensors_present_extended: MavSysStatusSensorExtended::DEFAULT,
28318 onboard_control_sensors_enabled_extended: MavSysStatusSensorExtended::DEFAULT,
28319 onboard_control_sensors_health_extended: MavSysStatusSensorExtended::DEFAULT,
28320 };
28321 #[cfg(feature = "arbitrary")]
28322 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28323 use arbitrary::{Arbitrary, Unstructured};
28324 let mut buf = [0u8; 1024];
28325 rng.fill_bytes(&mut buf);
28326 let mut unstructured = Unstructured::new(&buf);
28327 Self::arbitrary(&mut unstructured).unwrap_or_default()
28328 }
28329}
28330impl Default for SYS_STATUS_DATA {
28331 fn default() -> Self {
28332 Self::DEFAULT.clone()
28333 }
28334}
28335impl MessageData for SYS_STATUS_DATA {
28336 type Message = MavMessage;
28337 const ID: u32 = 1u32;
28338 const NAME: &'static str = "SYS_STATUS";
28339 const EXTRA_CRC: u8 = 124u8;
28340 const ENCODED_LEN: usize = 43usize;
28341 fn deser(
28342 _version: MavlinkVersion,
28343 __input: &[u8],
28344 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28345 let avail_len = __input.len();
28346 let mut payload_buf = [0; Self::ENCODED_LEN];
28347 let mut buf = if avail_len < Self::ENCODED_LEN {
28348 payload_buf[0..avail_len].copy_from_slice(__input);
28349 Bytes::new(&payload_buf)
28350 } else {
28351 Bytes::new(__input)
28352 };
28353 let mut __struct = Self::default();
28354 let tmp = buf.get_u32_le();
28355 __struct.onboard_control_sensors_present = MavSysStatusSensor::from_bits(
28356 tmp & MavSysStatusSensor::all().bits(),
28357 )
28358 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
28359 flag_type: "MavSysStatusSensor",
28360 value: tmp as u32,
28361 })?;
28362 let tmp = buf.get_u32_le();
28363 __struct.onboard_control_sensors_enabled = MavSysStatusSensor::from_bits(
28364 tmp & MavSysStatusSensor::all().bits(),
28365 )
28366 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
28367 flag_type: "MavSysStatusSensor",
28368 value: tmp as u32,
28369 })?;
28370 let tmp = buf.get_u32_le();
28371 __struct.onboard_control_sensors_health = MavSysStatusSensor::from_bits(
28372 tmp & MavSysStatusSensor::all().bits(),
28373 )
28374 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
28375 flag_type: "MavSysStatusSensor",
28376 value: tmp as u32,
28377 })?;
28378 __struct.load = buf.get_u16_le();
28379 __struct.voltage_battery = buf.get_u16_le();
28380 __struct.current_battery = buf.get_i16_le();
28381 __struct.drop_rate_comm = buf.get_u16_le();
28382 __struct.errors_comm = buf.get_u16_le();
28383 __struct.errors_count1 = buf.get_u16_le();
28384 __struct.errors_count2 = buf.get_u16_le();
28385 __struct.errors_count3 = buf.get_u16_le();
28386 __struct.errors_count4 = buf.get_u16_le();
28387 __struct.battery_remaining = buf.get_i8();
28388 let tmp = buf.get_u32_le();
28389 __struct.onboard_control_sensors_present_extended =
28390 MavSysStatusSensorExtended::from_bits(tmp & MavSysStatusSensorExtended::all().bits())
28391 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
28392 flag_type: "MavSysStatusSensorExtended",
28393 value: tmp as u32,
28394 })?;
28395 let tmp = buf.get_u32_le();
28396 __struct.onboard_control_sensors_enabled_extended =
28397 MavSysStatusSensorExtended::from_bits(tmp & MavSysStatusSensorExtended::all().bits())
28398 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
28399 flag_type: "MavSysStatusSensorExtended",
28400 value: tmp as u32,
28401 })?;
28402 let tmp = buf.get_u32_le();
28403 __struct.onboard_control_sensors_health_extended =
28404 MavSysStatusSensorExtended::from_bits(tmp & MavSysStatusSensorExtended::all().bits())
28405 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
28406 flag_type: "MavSysStatusSensorExtended",
28407 value: tmp as u32,
28408 })?;
28409 Ok(__struct)
28410 }
28411 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28412 let mut __tmp = BytesMut::new(bytes);
28413 #[allow(clippy::absurd_extreme_comparisons)]
28414 #[allow(unused_comparisons)]
28415 if __tmp.remaining() < Self::ENCODED_LEN {
28416 panic!(
28417 "buffer is too small (need {} bytes, but got {})",
28418 Self::ENCODED_LEN,
28419 __tmp.remaining(),
28420 )
28421 }
28422 __tmp.put_u32_le(self.onboard_control_sensors_present.bits());
28423 __tmp.put_u32_le(self.onboard_control_sensors_enabled.bits());
28424 __tmp.put_u32_le(self.onboard_control_sensors_health.bits());
28425 __tmp.put_u16_le(self.load);
28426 __tmp.put_u16_le(self.voltage_battery);
28427 __tmp.put_i16_le(self.current_battery);
28428 __tmp.put_u16_le(self.drop_rate_comm);
28429 __tmp.put_u16_le(self.errors_comm);
28430 __tmp.put_u16_le(self.errors_count1);
28431 __tmp.put_u16_le(self.errors_count2);
28432 __tmp.put_u16_le(self.errors_count3);
28433 __tmp.put_u16_le(self.errors_count4);
28434 __tmp.put_i8(self.battery_remaining);
28435 __tmp.put_u32_le(self.onboard_control_sensors_present_extended.bits());
28436 __tmp.put_u32_le(self.onboard_control_sensors_enabled_extended.bits());
28437 __tmp.put_u32_le(self.onboard_control_sensors_health_extended.bits());
28438 if matches!(version, MavlinkVersion::V2) {
28439 let len = __tmp.len();
28440 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28441 } else {
28442 __tmp.len()
28443 }
28444 }
28445}
28446#[doc = "id: 135"]
28447#[doc = "Request that the vehicle report terrain height at the given location (expected response is a TERRAIN_REPORT). Used by GCS to check if vehicle has all terrain data needed for a mission."]
28448#[derive(Debug, Clone, PartialEq)]
28449#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28450#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28451pub struct TERRAIN_CHECK_DATA {
28452 #[doc = "Latitude"]
28453 pub lat: i32,
28454 #[doc = "Longitude"]
28455 pub lon: i32,
28456}
28457impl TERRAIN_CHECK_DATA {
28458 pub const ENCODED_LEN: usize = 8usize;
28459 pub const DEFAULT: Self = Self {
28460 lat: 0_i32,
28461 lon: 0_i32,
28462 };
28463 #[cfg(feature = "arbitrary")]
28464 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28465 use arbitrary::{Arbitrary, Unstructured};
28466 let mut buf = [0u8; 1024];
28467 rng.fill_bytes(&mut buf);
28468 let mut unstructured = Unstructured::new(&buf);
28469 Self::arbitrary(&mut unstructured).unwrap_or_default()
28470 }
28471}
28472impl Default for TERRAIN_CHECK_DATA {
28473 fn default() -> Self {
28474 Self::DEFAULT.clone()
28475 }
28476}
28477impl MessageData for TERRAIN_CHECK_DATA {
28478 type Message = MavMessage;
28479 const ID: u32 = 135u32;
28480 const NAME: &'static str = "TERRAIN_CHECK";
28481 const EXTRA_CRC: u8 = 203u8;
28482 const ENCODED_LEN: usize = 8usize;
28483 fn deser(
28484 _version: MavlinkVersion,
28485 __input: &[u8],
28486 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28487 let avail_len = __input.len();
28488 let mut payload_buf = [0; Self::ENCODED_LEN];
28489 let mut buf = if avail_len < Self::ENCODED_LEN {
28490 payload_buf[0..avail_len].copy_from_slice(__input);
28491 Bytes::new(&payload_buf)
28492 } else {
28493 Bytes::new(__input)
28494 };
28495 let mut __struct = Self::default();
28496 __struct.lat = buf.get_i32_le();
28497 __struct.lon = buf.get_i32_le();
28498 Ok(__struct)
28499 }
28500 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28501 let mut __tmp = BytesMut::new(bytes);
28502 #[allow(clippy::absurd_extreme_comparisons)]
28503 #[allow(unused_comparisons)]
28504 if __tmp.remaining() < Self::ENCODED_LEN {
28505 panic!(
28506 "buffer is too small (need {} bytes, but got {})",
28507 Self::ENCODED_LEN,
28508 __tmp.remaining(),
28509 )
28510 }
28511 __tmp.put_i32_le(self.lat);
28512 __tmp.put_i32_le(self.lon);
28513 if matches!(version, MavlinkVersion::V2) {
28514 let len = __tmp.len();
28515 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28516 } else {
28517 __tmp.len()
28518 }
28519 }
28520}
28521#[doc = "id: 134"]
28522#[doc = "Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST. See terrain protocol docs: <https://mavlink.io/en/services/terrain.html>."]
28523#[derive(Debug, Clone, PartialEq)]
28524#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28525#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28526pub struct TERRAIN_DATA_DATA {
28527 #[doc = "Latitude of SW corner of first grid"]
28528 pub lat: i32,
28529 #[doc = "Longitude of SW corner of first grid"]
28530 pub lon: i32,
28531 #[doc = "Grid spacing"]
28532 pub grid_spacing: u16,
28533 #[doc = "Terrain data MSL"]
28534 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28535 pub data: [i16; 16],
28536 #[doc = "bit within the terrain request mask"]
28537 pub gridbit: u8,
28538}
28539impl TERRAIN_DATA_DATA {
28540 pub const ENCODED_LEN: usize = 43usize;
28541 pub const DEFAULT: Self = Self {
28542 lat: 0_i32,
28543 lon: 0_i32,
28544 grid_spacing: 0_u16,
28545 data: [0_i16; 16usize],
28546 gridbit: 0_u8,
28547 };
28548 #[cfg(feature = "arbitrary")]
28549 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28550 use arbitrary::{Arbitrary, Unstructured};
28551 let mut buf = [0u8; 1024];
28552 rng.fill_bytes(&mut buf);
28553 let mut unstructured = Unstructured::new(&buf);
28554 Self::arbitrary(&mut unstructured).unwrap_or_default()
28555 }
28556}
28557impl Default for TERRAIN_DATA_DATA {
28558 fn default() -> Self {
28559 Self::DEFAULT.clone()
28560 }
28561}
28562impl MessageData for TERRAIN_DATA_DATA {
28563 type Message = MavMessage;
28564 const ID: u32 = 134u32;
28565 const NAME: &'static str = "TERRAIN_DATA";
28566 const EXTRA_CRC: u8 = 229u8;
28567 const ENCODED_LEN: usize = 43usize;
28568 fn deser(
28569 _version: MavlinkVersion,
28570 __input: &[u8],
28571 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28572 let avail_len = __input.len();
28573 let mut payload_buf = [0; Self::ENCODED_LEN];
28574 let mut buf = if avail_len < Self::ENCODED_LEN {
28575 payload_buf[0..avail_len].copy_from_slice(__input);
28576 Bytes::new(&payload_buf)
28577 } else {
28578 Bytes::new(__input)
28579 };
28580 let mut __struct = Self::default();
28581 __struct.lat = buf.get_i32_le();
28582 __struct.lon = buf.get_i32_le();
28583 __struct.grid_spacing = buf.get_u16_le();
28584 for v in &mut __struct.data {
28585 let val = buf.get_i16_le();
28586 *v = val;
28587 }
28588 __struct.gridbit = buf.get_u8();
28589 Ok(__struct)
28590 }
28591 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28592 let mut __tmp = BytesMut::new(bytes);
28593 #[allow(clippy::absurd_extreme_comparisons)]
28594 #[allow(unused_comparisons)]
28595 if __tmp.remaining() < Self::ENCODED_LEN {
28596 panic!(
28597 "buffer is too small (need {} bytes, but got {})",
28598 Self::ENCODED_LEN,
28599 __tmp.remaining(),
28600 )
28601 }
28602 __tmp.put_i32_le(self.lat);
28603 __tmp.put_i32_le(self.lon);
28604 __tmp.put_u16_le(self.grid_spacing);
28605 for val in &self.data {
28606 __tmp.put_i16_le(*val);
28607 }
28608 __tmp.put_u8(self.gridbit);
28609 if matches!(version, MavlinkVersion::V2) {
28610 let len = __tmp.len();
28611 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28612 } else {
28613 __tmp.len()
28614 }
28615 }
28616}
28617#[doc = "id: 136"]
28618#[doc = "Streamed from drone to report progress of terrain map download (initiated by TERRAIN_REQUEST), or sent as a response to a TERRAIN_CHECK request. See terrain protocol docs: <https://mavlink.io/en/services/terrain.html>."]
28619#[derive(Debug, Clone, PartialEq)]
28620#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28621#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28622pub struct TERRAIN_REPORT_DATA {
28623 #[doc = "Latitude"]
28624 pub lat: i32,
28625 #[doc = "Longitude"]
28626 pub lon: i32,
28627 #[doc = "Terrain height MSL"]
28628 pub terrain_height: f32,
28629 #[doc = "Current vehicle height above lat/lon terrain height"]
28630 pub current_height: f32,
28631 #[doc = "grid spacing (zero if terrain at this location unavailable)"]
28632 pub spacing: u16,
28633 #[doc = "Number of 4x4 terrain blocks waiting to be received or read from disk"]
28634 pub pending: u16,
28635 #[doc = "Number of 4x4 terrain blocks in memory"]
28636 pub loaded: u16,
28637}
28638impl TERRAIN_REPORT_DATA {
28639 pub const ENCODED_LEN: usize = 22usize;
28640 pub const DEFAULT: Self = Self {
28641 lat: 0_i32,
28642 lon: 0_i32,
28643 terrain_height: 0.0_f32,
28644 current_height: 0.0_f32,
28645 spacing: 0_u16,
28646 pending: 0_u16,
28647 loaded: 0_u16,
28648 };
28649 #[cfg(feature = "arbitrary")]
28650 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28651 use arbitrary::{Arbitrary, Unstructured};
28652 let mut buf = [0u8; 1024];
28653 rng.fill_bytes(&mut buf);
28654 let mut unstructured = Unstructured::new(&buf);
28655 Self::arbitrary(&mut unstructured).unwrap_or_default()
28656 }
28657}
28658impl Default for TERRAIN_REPORT_DATA {
28659 fn default() -> Self {
28660 Self::DEFAULT.clone()
28661 }
28662}
28663impl MessageData for TERRAIN_REPORT_DATA {
28664 type Message = MavMessage;
28665 const ID: u32 = 136u32;
28666 const NAME: &'static str = "TERRAIN_REPORT";
28667 const EXTRA_CRC: u8 = 1u8;
28668 const ENCODED_LEN: usize = 22usize;
28669 fn deser(
28670 _version: MavlinkVersion,
28671 __input: &[u8],
28672 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28673 let avail_len = __input.len();
28674 let mut payload_buf = [0; Self::ENCODED_LEN];
28675 let mut buf = if avail_len < Self::ENCODED_LEN {
28676 payload_buf[0..avail_len].copy_from_slice(__input);
28677 Bytes::new(&payload_buf)
28678 } else {
28679 Bytes::new(__input)
28680 };
28681 let mut __struct = Self::default();
28682 __struct.lat = buf.get_i32_le();
28683 __struct.lon = buf.get_i32_le();
28684 __struct.terrain_height = buf.get_f32_le();
28685 __struct.current_height = buf.get_f32_le();
28686 __struct.spacing = buf.get_u16_le();
28687 __struct.pending = buf.get_u16_le();
28688 __struct.loaded = buf.get_u16_le();
28689 Ok(__struct)
28690 }
28691 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28692 let mut __tmp = BytesMut::new(bytes);
28693 #[allow(clippy::absurd_extreme_comparisons)]
28694 #[allow(unused_comparisons)]
28695 if __tmp.remaining() < Self::ENCODED_LEN {
28696 panic!(
28697 "buffer is too small (need {} bytes, but got {})",
28698 Self::ENCODED_LEN,
28699 __tmp.remaining(),
28700 )
28701 }
28702 __tmp.put_i32_le(self.lat);
28703 __tmp.put_i32_le(self.lon);
28704 __tmp.put_f32_le(self.terrain_height);
28705 __tmp.put_f32_le(self.current_height);
28706 __tmp.put_u16_le(self.spacing);
28707 __tmp.put_u16_le(self.pending);
28708 __tmp.put_u16_le(self.loaded);
28709 if matches!(version, MavlinkVersion::V2) {
28710 let len = __tmp.len();
28711 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28712 } else {
28713 __tmp.len()
28714 }
28715 }
28716}
28717#[doc = "id: 133"]
28718#[doc = "Request for terrain data and terrain status. See terrain protocol docs: <https://mavlink.io/en/services/terrain.html>."]
28719#[derive(Debug, Clone, PartialEq)]
28720#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28721#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28722pub struct TERRAIN_REQUEST_DATA {
28723 #[doc = "Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)"]
28724 pub mask: u64,
28725 #[doc = "Latitude of SW corner of first grid"]
28726 pub lat: i32,
28727 #[doc = "Longitude of SW corner of first grid"]
28728 pub lon: i32,
28729 #[doc = "Grid spacing"]
28730 pub grid_spacing: u16,
28731}
28732impl TERRAIN_REQUEST_DATA {
28733 pub const ENCODED_LEN: usize = 18usize;
28734 pub const DEFAULT: Self = Self {
28735 mask: 0_u64,
28736 lat: 0_i32,
28737 lon: 0_i32,
28738 grid_spacing: 0_u16,
28739 };
28740 #[cfg(feature = "arbitrary")]
28741 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28742 use arbitrary::{Arbitrary, Unstructured};
28743 let mut buf = [0u8; 1024];
28744 rng.fill_bytes(&mut buf);
28745 let mut unstructured = Unstructured::new(&buf);
28746 Self::arbitrary(&mut unstructured).unwrap_or_default()
28747 }
28748}
28749impl Default for TERRAIN_REQUEST_DATA {
28750 fn default() -> Self {
28751 Self::DEFAULT.clone()
28752 }
28753}
28754impl MessageData for TERRAIN_REQUEST_DATA {
28755 type Message = MavMessage;
28756 const ID: u32 = 133u32;
28757 const NAME: &'static str = "TERRAIN_REQUEST";
28758 const EXTRA_CRC: u8 = 6u8;
28759 const ENCODED_LEN: usize = 18usize;
28760 fn deser(
28761 _version: MavlinkVersion,
28762 __input: &[u8],
28763 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28764 let avail_len = __input.len();
28765 let mut payload_buf = [0; Self::ENCODED_LEN];
28766 let mut buf = if avail_len < Self::ENCODED_LEN {
28767 payload_buf[0..avail_len].copy_from_slice(__input);
28768 Bytes::new(&payload_buf)
28769 } else {
28770 Bytes::new(__input)
28771 };
28772 let mut __struct = Self::default();
28773 __struct.mask = buf.get_u64_le();
28774 __struct.lat = buf.get_i32_le();
28775 __struct.lon = buf.get_i32_le();
28776 __struct.grid_spacing = buf.get_u16_le();
28777 Ok(__struct)
28778 }
28779 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28780 let mut __tmp = BytesMut::new(bytes);
28781 #[allow(clippy::absurd_extreme_comparisons)]
28782 #[allow(unused_comparisons)]
28783 if __tmp.remaining() < Self::ENCODED_LEN {
28784 panic!(
28785 "buffer is too small (need {} bytes, but got {})",
28786 Self::ENCODED_LEN,
28787 __tmp.remaining(),
28788 )
28789 }
28790 __tmp.put_u64_le(self.mask);
28791 __tmp.put_i32_le(self.lat);
28792 __tmp.put_i32_le(self.lon);
28793 __tmp.put_u16_le(self.grid_spacing);
28794 if matches!(version, MavlinkVersion::V2) {
28795 let len = __tmp.len();
28796 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28797 } else {
28798 __tmp.len()
28799 }
28800 }
28801}
28802#[doc = "id: 111"]
28803#[doc = "Time synchronization message. The message is used for both timesync requests and responses. The request is sent with `ts1=syncing component timestamp` and `tc1=0`, and may be broadcast or targeted to a specific system/component. The response is sent with `ts1=syncing component timestamp` (mirror back unchanged), and `tc1=responding component timestamp`, with the `target_system` and `target_component` set to ids of the original request. Systems can determine if they are receiving a request or response based on the value of `tc`. If the response has `target_system==target_component==0` the remote system has not been updated to use the component IDs and cannot reliably timesync; the requestor may report an error. Timestamps are UNIX Epoch time or time since system boot in nanoseconds (the timestamp format can be inferred by checking for the magnitude of the number; generally it doesn't matter as only the offset is used). The message sequence is repeated numerous times with results being filtered/averaged to estimate the offset. See also: <https://mavlink.io/en/services/timesync.html>."]
28804#[derive(Debug, Clone, PartialEq)]
28805#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28806#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28807pub struct TIMESYNC_DATA {
28808 #[doc = "Time sync timestamp 1. Syncing: 0. Responding: Timestamp of responding component."]
28809 pub tc1: i64,
28810 #[doc = "Time sync timestamp 2. Timestamp of syncing component (mirrored in response)."]
28811 pub ts1: i64,
28812 #[doc = "Target system id. Request: 0 (broadcast) or id of specific system. Response must contain system id of the requesting component."]
28813 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28814 pub target_system: u8,
28815 #[doc = "Target component id. Request: 0 (broadcast) or id of specific component. Response must contain component id of the requesting component."]
28816 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28817 pub target_component: u8,
28818}
28819impl TIMESYNC_DATA {
28820 pub const ENCODED_LEN: usize = 18usize;
28821 pub const DEFAULT: Self = Self {
28822 tc1: 0_i64,
28823 ts1: 0_i64,
28824 target_system: 0_u8,
28825 target_component: 0_u8,
28826 };
28827 #[cfg(feature = "arbitrary")]
28828 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28829 use arbitrary::{Arbitrary, Unstructured};
28830 let mut buf = [0u8; 1024];
28831 rng.fill_bytes(&mut buf);
28832 let mut unstructured = Unstructured::new(&buf);
28833 Self::arbitrary(&mut unstructured).unwrap_or_default()
28834 }
28835}
28836impl Default for TIMESYNC_DATA {
28837 fn default() -> Self {
28838 Self::DEFAULT.clone()
28839 }
28840}
28841impl MessageData for TIMESYNC_DATA {
28842 type Message = MavMessage;
28843 const ID: u32 = 111u32;
28844 const NAME: &'static str = "TIMESYNC";
28845 const EXTRA_CRC: u8 = 34u8;
28846 const ENCODED_LEN: usize = 18usize;
28847 fn deser(
28848 _version: MavlinkVersion,
28849 __input: &[u8],
28850 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28851 let avail_len = __input.len();
28852 let mut payload_buf = [0; Self::ENCODED_LEN];
28853 let mut buf = if avail_len < Self::ENCODED_LEN {
28854 payload_buf[0..avail_len].copy_from_slice(__input);
28855 Bytes::new(&payload_buf)
28856 } else {
28857 Bytes::new(__input)
28858 };
28859 let mut __struct = Self::default();
28860 __struct.tc1 = buf.get_i64_le();
28861 __struct.ts1 = buf.get_i64_le();
28862 __struct.target_system = buf.get_u8();
28863 __struct.target_component = buf.get_u8();
28864 Ok(__struct)
28865 }
28866 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28867 let mut __tmp = BytesMut::new(bytes);
28868 #[allow(clippy::absurd_extreme_comparisons)]
28869 #[allow(unused_comparisons)]
28870 if __tmp.remaining() < Self::ENCODED_LEN {
28871 panic!(
28872 "buffer is too small (need {} bytes, but got {})",
28873 Self::ENCODED_LEN,
28874 __tmp.remaining(),
28875 )
28876 }
28877 __tmp.put_i64_le(self.tc1);
28878 __tmp.put_i64_le(self.ts1);
28879 __tmp.put_u8(self.target_system);
28880 __tmp.put_u8(self.target_component);
28881 if matches!(version, MavlinkVersion::V2) {
28882 let len = __tmp.len();
28883 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28884 } else {
28885 __tmp.len()
28886 }
28887 }
28888}
28889#[doc = "id: 380"]
28890#[doc = "Time/duration estimates for various events and actions given the current vehicle state and position."]
28891#[derive(Debug, Clone, PartialEq)]
28892#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28893#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28894pub struct TIME_ESTIMATE_TO_TARGET_DATA {
28895 #[doc = "Estimated time to complete the vehicle's configured \"safe return\" action from its current position (e.g. RTL, Smart RTL, etc.). -1 indicates that the vehicle is landed, or that no time estimate available."]
28896 pub safe_return: i32,
28897 #[doc = "Estimated time for vehicle to complete the LAND action from its current position. -1 indicates that the vehicle is landed, or that no time estimate available."]
28898 pub land: i32,
28899 #[doc = "Estimated time for reaching/completing the currently active mission item. -1 means no time estimate available."]
28900 pub mission_next_item: i32,
28901 #[doc = "Estimated time for completing the current mission. -1 means no mission active and/or no estimate available."]
28902 pub mission_end: i32,
28903 #[doc = "Estimated time for completing the current commanded action (i.e. Go To, Takeoff, Land, etc.). -1 means no action active and/or no estimate available."]
28904 pub commanded_action: i32,
28905}
28906impl TIME_ESTIMATE_TO_TARGET_DATA {
28907 pub const ENCODED_LEN: usize = 20usize;
28908 pub const DEFAULT: Self = Self {
28909 safe_return: 0_i32,
28910 land: 0_i32,
28911 mission_next_item: 0_i32,
28912 mission_end: 0_i32,
28913 commanded_action: 0_i32,
28914 };
28915 #[cfg(feature = "arbitrary")]
28916 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28917 use arbitrary::{Arbitrary, Unstructured};
28918 let mut buf = [0u8; 1024];
28919 rng.fill_bytes(&mut buf);
28920 let mut unstructured = Unstructured::new(&buf);
28921 Self::arbitrary(&mut unstructured).unwrap_or_default()
28922 }
28923}
28924impl Default for TIME_ESTIMATE_TO_TARGET_DATA {
28925 fn default() -> Self {
28926 Self::DEFAULT.clone()
28927 }
28928}
28929impl MessageData for TIME_ESTIMATE_TO_TARGET_DATA {
28930 type Message = MavMessage;
28931 const ID: u32 = 380u32;
28932 const NAME: &'static str = "TIME_ESTIMATE_TO_TARGET";
28933 const EXTRA_CRC: u8 = 232u8;
28934 const ENCODED_LEN: usize = 20usize;
28935 fn deser(
28936 _version: MavlinkVersion,
28937 __input: &[u8],
28938 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28939 let avail_len = __input.len();
28940 let mut payload_buf = [0; Self::ENCODED_LEN];
28941 let mut buf = if avail_len < Self::ENCODED_LEN {
28942 payload_buf[0..avail_len].copy_from_slice(__input);
28943 Bytes::new(&payload_buf)
28944 } else {
28945 Bytes::new(__input)
28946 };
28947 let mut __struct = Self::default();
28948 __struct.safe_return = buf.get_i32_le();
28949 __struct.land = buf.get_i32_le();
28950 __struct.mission_next_item = buf.get_i32_le();
28951 __struct.mission_end = buf.get_i32_le();
28952 __struct.commanded_action = buf.get_i32_le();
28953 Ok(__struct)
28954 }
28955 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28956 let mut __tmp = BytesMut::new(bytes);
28957 #[allow(clippy::absurd_extreme_comparisons)]
28958 #[allow(unused_comparisons)]
28959 if __tmp.remaining() < Self::ENCODED_LEN {
28960 panic!(
28961 "buffer is too small (need {} bytes, but got {})",
28962 Self::ENCODED_LEN,
28963 __tmp.remaining(),
28964 )
28965 }
28966 __tmp.put_i32_le(self.safe_return);
28967 __tmp.put_i32_le(self.land);
28968 __tmp.put_i32_le(self.mission_next_item);
28969 __tmp.put_i32_le(self.mission_end);
28970 __tmp.put_i32_le(self.commanded_action);
28971 if matches!(version, MavlinkVersion::V2) {
28972 let len = __tmp.len();
28973 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28974 } else {
28975 __tmp.len()
28976 }
28977 }
28978}
28979#[doc = "id: 333"]
28980#[doc = "Describe a trajectory using an array of up-to 5 bezier control points in the local frame (MAV_FRAME_LOCAL_NED)."]
28981#[derive(Debug, Clone, PartialEq)]
28982#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28983#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28984pub struct TRAJECTORY_REPRESENTATION_BEZIER_DATA {
28985 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
28986 pub time_usec: u64,
28987 #[doc = "X-coordinate of bezier control points. Set to NaN if not being used"]
28988 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28989 pub pos_x: [f32; 5],
28990 #[doc = "Y-coordinate of bezier control points. Set to NaN if not being used"]
28991 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28992 pub pos_y: [f32; 5],
28993 #[doc = "Z-coordinate of bezier control points. Set to NaN if not being used"]
28994 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28995 pub pos_z: [f32; 5],
28996 #[doc = "Bezier time horizon. Set to NaN if velocity/acceleration should not be incorporated"]
28997 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28998 pub delta: [f32; 5],
28999 #[doc = "Yaw. Set to NaN for unchanged"]
29000 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29001 pub pos_yaw: [f32; 5],
29002 #[doc = "Number of valid control points (up-to 5 points are possible)"]
29003 pub valid_points: u8,
29004}
29005impl TRAJECTORY_REPRESENTATION_BEZIER_DATA {
29006 pub const ENCODED_LEN: usize = 109usize;
29007 pub const DEFAULT: Self = Self {
29008 time_usec: 0_u64,
29009 pos_x: [0.0_f32; 5usize],
29010 pos_y: [0.0_f32; 5usize],
29011 pos_z: [0.0_f32; 5usize],
29012 delta: [0.0_f32; 5usize],
29013 pos_yaw: [0.0_f32; 5usize],
29014 valid_points: 0_u8,
29015 };
29016 #[cfg(feature = "arbitrary")]
29017 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29018 use arbitrary::{Arbitrary, Unstructured};
29019 let mut buf = [0u8; 1024];
29020 rng.fill_bytes(&mut buf);
29021 let mut unstructured = Unstructured::new(&buf);
29022 Self::arbitrary(&mut unstructured).unwrap_or_default()
29023 }
29024}
29025impl Default for TRAJECTORY_REPRESENTATION_BEZIER_DATA {
29026 fn default() -> Self {
29027 Self::DEFAULT.clone()
29028 }
29029}
29030impl MessageData for TRAJECTORY_REPRESENTATION_BEZIER_DATA {
29031 type Message = MavMessage;
29032 const ID: u32 = 333u32;
29033 const NAME: &'static str = "TRAJECTORY_REPRESENTATION_BEZIER";
29034 const EXTRA_CRC: u8 = 231u8;
29035 const ENCODED_LEN: usize = 109usize;
29036 fn deser(
29037 _version: MavlinkVersion,
29038 __input: &[u8],
29039 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29040 let avail_len = __input.len();
29041 let mut payload_buf = [0; Self::ENCODED_LEN];
29042 let mut buf = if avail_len < Self::ENCODED_LEN {
29043 payload_buf[0..avail_len].copy_from_slice(__input);
29044 Bytes::new(&payload_buf)
29045 } else {
29046 Bytes::new(__input)
29047 };
29048 let mut __struct = Self::default();
29049 __struct.time_usec = buf.get_u64_le();
29050 for v in &mut __struct.pos_x {
29051 let val = buf.get_f32_le();
29052 *v = val;
29053 }
29054 for v in &mut __struct.pos_y {
29055 let val = buf.get_f32_le();
29056 *v = val;
29057 }
29058 for v in &mut __struct.pos_z {
29059 let val = buf.get_f32_le();
29060 *v = val;
29061 }
29062 for v in &mut __struct.delta {
29063 let val = buf.get_f32_le();
29064 *v = val;
29065 }
29066 for v in &mut __struct.pos_yaw {
29067 let val = buf.get_f32_le();
29068 *v = val;
29069 }
29070 __struct.valid_points = buf.get_u8();
29071 Ok(__struct)
29072 }
29073 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29074 let mut __tmp = BytesMut::new(bytes);
29075 #[allow(clippy::absurd_extreme_comparisons)]
29076 #[allow(unused_comparisons)]
29077 if __tmp.remaining() < Self::ENCODED_LEN {
29078 panic!(
29079 "buffer is too small (need {} bytes, but got {})",
29080 Self::ENCODED_LEN,
29081 __tmp.remaining(),
29082 )
29083 }
29084 __tmp.put_u64_le(self.time_usec);
29085 for val in &self.pos_x {
29086 __tmp.put_f32_le(*val);
29087 }
29088 for val in &self.pos_y {
29089 __tmp.put_f32_le(*val);
29090 }
29091 for val in &self.pos_z {
29092 __tmp.put_f32_le(*val);
29093 }
29094 for val in &self.delta {
29095 __tmp.put_f32_le(*val);
29096 }
29097 for val in &self.pos_yaw {
29098 __tmp.put_f32_le(*val);
29099 }
29100 __tmp.put_u8(self.valid_points);
29101 if matches!(version, MavlinkVersion::V2) {
29102 let len = __tmp.len();
29103 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29104 } else {
29105 __tmp.len()
29106 }
29107 }
29108}
29109#[doc = "id: 332"]
29110#[doc = "Describe a trajectory using an array of up-to 5 waypoints in the local frame (MAV_FRAME_LOCAL_NED)."]
29111#[derive(Debug, Clone, PartialEq)]
29112#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29113#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29114pub struct TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
29115 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
29116 pub time_usec: u64,
29117 #[doc = "X-coordinate of waypoint, set to NaN if not being used"]
29118 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29119 pub pos_x: [f32; 5],
29120 #[doc = "Y-coordinate of waypoint, set to NaN if not being used"]
29121 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29122 pub pos_y: [f32; 5],
29123 #[doc = "Z-coordinate of waypoint, set to NaN if not being used"]
29124 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29125 pub pos_z: [f32; 5],
29126 #[doc = "X-velocity of waypoint, set to NaN if not being used"]
29127 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29128 pub vel_x: [f32; 5],
29129 #[doc = "Y-velocity of waypoint, set to NaN if not being used"]
29130 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29131 pub vel_y: [f32; 5],
29132 #[doc = "Z-velocity of waypoint, set to NaN if not being used"]
29133 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29134 pub vel_z: [f32; 5],
29135 #[doc = "X-acceleration of waypoint, set to NaN if not being used"]
29136 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29137 pub acc_x: [f32; 5],
29138 #[doc = "Y-acceleration of waypoint, set to NaN if not being used"]
29139 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29140 pub acc_y: [f32; 5],
29141 #[doc = "Z-acceleration of waypoint, set to NaN if not being used"]
29142 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29143 pub acc_z: [f32; 5],
29144 #[doc = "Yaw angle, set to NaN if not being used"]
29145 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29146 pub pos_yaw: [f32; 5],
29147 #[doc = "Yaw rate, set to NaN if not being used"]
29148 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29149 pub vel_yaw: [f32; 5],
29150 #[doc = "MAV_CMD command id of waypoint, set to UINT16_MAX if not being used."]
29151 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29152 pub command: [u16; 5],
29153 #[doc = "Number of valid points (up-to 5 waypoints are possible)"]
29154 pub valid_points: u8,
29155}
29156impl TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
29157 pub const ENCODED_LEN: usize = 239usize;
29158 pub const DEFAULT: Self = Self {
29159 time_usec: 0_u64,
29160 pos_x: [0.0_f32; 5usize],
29161 pos_y: [0.0_f32; 5usize],
29162 pos_z: [0.0_f32; 5usize],
29163 vel_x: [0.0_f32; 5usize],
29164 vel_y: [0.0_f32; 5usize],
29165 vel_z: [0.0_f32; 5usize],
29166 acc_x: [0.0_f32; 5usize],
29167 acc_y: [0.0_f32; 5usize],
29168 acc_z: [0.0_f32; 5usize],
29169 pos_yaw: [0.0_f32; 5usize],
29170 vel_yaw: [0.0_f32; 5usize],
29171 command: [0_u16; 5usize],
29172 valid_points: 0_u8,
29173 };
29174 #[cfg(feature = "arbitrary")]
29175 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29176 use arbitrary::{Arbitrary, Unstructured};
29177 let mut buf = [0u8; 1024];
29178 rng.fill_bytes(&mut buf);
29179 let mut unstructured = Unstructured::new(&buf);
29180 Self::arbitrary(&mut unstructured).unwrap_or_default()
29181 }
29182}
29183impl Default for TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
29184 fn default() -> Self {
29185 Self::DEFAULT.clone()
29186 }
29187}
29188impl MessageData for TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
29189 type Message = MavMessage;
29190 const ID: u32 = 332u32;
29191 const NAME: &'static str = "TRAJECTORY_REPRESENTATION_WAYPOINTS";
29192 const EXTRA_CRC: u8 = 236u8;
29193 const ENCODED_LEN: usize = 239usize;
29194 fn deser(
29195 _version: MavlinkVersion,
29196 __input: &[u8],
29197 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29198 let avail_len = __input.len();
29199 let mut payload_buf = [0; Self::ENCODED_LEN];
29200 let mut buf = if avail_len < Self::ENCODED_LEN {
29201 payload_buf[0..avail_len].copy_from_slice(__input);
29202 Bytes::new(&payload_buf)
29203 } else {
29204 Bytes::new(__input)
29205 };
29206 let mut __struct = Self::default();
29207 __struct.time_usec = buf.get_u64_le();
29208 for v in &mut __struct.pos_x {
29209 let val = buf.get_f32_le();
29210 *v = val;
29211 }
29212 for v in &mut __struct.pos_y {
29213 let val = buf.get_f32_le();
29214 *v = val;
29215 }
29216 for v in &mut __struct.pos_z {
29217 let val = buf.get_f32_le();
29218 *v = val;
29219 }
29220 for v in &mut __struct.vel_x {
29221 let val = buf.get_f32_le();
29222 *v = val;
29223 }
29224 for v in &mut __struct.vel_y {
29225 let val = buf.get_f32_le();
29226 *v = val;
29227 }
29228 for v in &mut __struct.vel_z {
29229 let val = buf.get_f32_le();
29230 *v = val;
29231 }
29232 for v in &mut __struct.acc_x {
29233 let val = buf.get_f32_le();
29234 *v = val;
29235 }
29236 for v in &mut __struct.acc_y {
29237 let val = buf.get_f32_le();
29238 *v = val;
29239 }
29240 for v in &mut __struct.acc_z {
29241 let val = buf.get_f32_le();
29242 *v = val;
29243 }
29244 for v in &mut __struct.pos_yaw {
29245 let val = buf.get_f32_le();
29246 *v = val;
29247 }
29248 for v in &mut __struct.vel_yaw {
29249 let val = buf.get_f32_le();
29250 *v = val;
29251 }
29252 for v in &mut __struct.command {
29253 let val = buf.get_u16_le();
29254 *v = val;
29255 }
29256 __struct.valid_points = buf.get_u8();
29257 Ok(__struct)
29258 }
29259 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29260 let mut __tmp = BytesMut::new(bytes);
29261 #[allow(clippy::absurd_extreme_comparisons)]
29262 #[allow(unused_comparisons)]
29263 if __tmp.remaining() < Self::ENCODED_LEN {
29264 panic!(
29265 "buffer is too small (need {} bytes, but got {})",
29266 Self::ENCODED_LEN,
29267 __tmp.remaining(),
29268 )
29269 }
29270 __tmp.put_u64_le(self.time_usec);
29271 for val in &self.pos_x {
29272 __tmp.put_f32_le(*val);
29273 }
29274 for val in &self.pos_y {
29275 __tmp.put_f32_le(*val);
29276 }
29277 for val in &self.pos_z {
29278 __tmp.put_f32_le(*val);
29279 }
29280 for val in &self.vel_x {
29281 __tmp.put_f32_le(*val);
29282 }
29283 for val in &self.vel_y {
29284 __tmp.put_f32_le(*val);
29285 }
29286 for val in &self.vel_z {
29287 __tmp.put_f32_le(*val);
29288 }
29289 for val in &self.acc_x {
29290 __tmp.put_f32_le(*val);
29291 }
29292 for val in &self.acc_y {
29293 __tmp.put_f32_le(*val);
29294 }
29295 for val in &self.acc_z {
29296 __tmp.put_f32_le(*val);
29297 }
29298 for val in &self.pos_yaw {
29299 __tmp.put_f32_le(*val);
29300 }
29301 for val in &self.vel_yaw {
29302 __tmp.put_f32_le(*val);
29303 }
29304 for val in &self.command {
29305 __tmp.put_u16_le(*val);
29306 }
29307 __tmp.put_u8(self.valid_points);
29308 if matches!(version, MavlinkVersion::V2) {
29309 let len = __tmp.len();
29310 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29311 } else {
29312 __tmp.len()
29313 }
29314 }
29315}
29316#[doc = "id: 385"]
29317#[doc = "Message for transporting \"arbitrary\" variable-length data from one component to another (broadcast is not forbidden, but discouraged). The encoding of the data is usually extension specific, i.e. determined by the source, and is usually not documented as part of the MAVLink specification."]
29318#[derive(Debug, Clone, PartialEq)]
29319#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29320#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29321pub struct TUNNEL_DATA {
29322 #[doc = "A code that identifies the content of the payload (0 for unknown, which is the default). If this code is less than 32768, it is a 'registered' payload type and the corresponding code should be added to the MAV_TUNNEL_PAYLOAD_TYPE enum. Software creators can register blocks of types as needed. Codes greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase."]
29323 pub payload_type: MavTunnelPayloadType,
29324 #[doc = "System ID (can be 0 for broadcast, but this is discouraged)"]
29325 pub target_system: u8,
29326 #[doc = "Component ID (can be 0 for broadcast, but this is discouraged)"]
29327 pub target_component: u8,
29328 #[doc = "Length of the data transported in payload"]
29329 pub payload_length: u8,
29330 #[doc = "Variable length payload. The payload length is defined by payload_length. The entire content of this block is opaque unless you understand the encoding specified by payload_type."]
29331 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29332 pub payload: [u8; 128],
29333}
29334impl TUNNEL_DATA {
29335 pub const ENCODED_LEN: usize = 133usize;
29336 pub const DEFAULT: Self = Self {
29337 payload_type: MavTunnelPayloadType::DEFAULT,
29338 target_system: 0_u8,
29339 target_component: 0_u8,
29340 payload_length: 0_u8,
29341 payload: [0_u8; 128usize],
29342 };
29343 #[cfg(feature = "arbitrary")]
29344 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29345 use arbitrary::{Arbitrary, Unstructured};
29346 let mut buf = [0u8; 1024];
29347 rng.fill_bytes(&mut buf);
29348 let mut unstructured = Unstructured::new(&buf);
29349 Self::arbitrary(&mut unstructured).unwrap_or_default()
29350 }
29351}
29352impl Default for TUNNEL_DATA {
29353 fn default() -> Self {
29354 Self::DEFAULT.clone()
29355 }
29356}
29357impl MessageData for TUNNEL_DATA {
29358 type Message = MavMessage;
29359 const ID: u32 = 385u32;
29360 const NAME: &'static str = "TUNNEL";
29361 const EXTRA_CRC: u8 = 147u8;
29362 const ENCODED_LEN: usize = 133usize;
29363 fn deser(
29364 _version: MavlinkVersion,
29365 __input: &[u8],
29366 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29367 let avail_len = __input.len();
29368 let mut payload_buf = [0; Self::ENCODED_LEN];
29369 let mut buf = if avail_len < Self::ENCODED_LEN {
29370 payload_buf[0..avail_len].copy_from_slice(__input);
29371 Bytes::new(&payload_buf)
29372 } else {
29373 Bytes::new(__input)
29374 };
29375 let mut __struct = Self::default();
29376 let tmp = buf.get_u16_le();
29377 __struct.payload_type = FromPrimitive::from_u16(tmp).ok_or(
29378 ::mavlink_core::error::ParserError::InvalidEnum {
29379 enum_type: "MavTunnelPayloadType",
29380 value: tmp as u32,
29381 },
29382 )?;
29383 __struct.target_system = buf.get_u8();
29384 __struct.target_component = buf.get_u8();
29385 __struct.payload_length = buf.get_u8();
29386 for v in &mut __struct.payload {
29387 let val = buf.get_u8();
29388 *v = val;
29389 }
29390 Ok(__struct)
29391 }
29392 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29393 let mut __tmp = BytesMut::new(bytes);
29394 #[allow(clippy::absurd_extreme_comparisons)]
29395 #[allow(unused_comparisons)]
29396 if __tmp.remaining() < Self::ENCODED_LEN {
29397 panic!(
29398 "buffer is too small (need {} bytes, but got {})",
29399 Self::ENCODED_LEN,
29400 __tmp.remaining(),
29401 )
29402 }
29403 __tmp.put_u16_le(self.payload_type as u16);
29404 __tmp.put_u8(self.target_system);
29405 __tmp.put_u8(self.target_component);
29406 __tmp.put_u8(self.payload_length);
29407 for val in &self.payload {
29408 __tmp.put_u8(*val);
29409 }
29410 if matches!(version, MavlinkVersion::V2) {
29411 let len = __tmp.len();
29412 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29413 } else {
29414 __tmp.len()
29415 }
29416 }
29417}
29418#[doc = "id: 311"]
29419#[doc = "General information describing a particular UAVCAN node. Please refer to the definition of the UAVCAN service \"uavcan.protocol.GetNodeInfo\" for the background information. This message should be emitted by the system whenever a new node appears online, or an existing node reboots. Additionally, it can be emitted upon request from the other end of the MAVLink channel (see MAV_CMD_UAVCAN_GET_NODE_INFO). It is also not prohibited to emit this message unconditionally at a low frequency. The UAVCAN specification is available at <http://uavcan.org>."]
29420#[derive(Debug, Clone, PartialEq)]
29421#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29422#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29423pub struct UAVCAN_NODE_INFO_DATA {
29424 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
29425 pub time_usec: u64,
29426 #[doc = "Time since the start-up of the node."]
29427 pub uptime_sec: u32,
29428 #[doc = "Version control system (VCS) revision identifier (e.g. git short commit hash). 0 if unknown."]
29429 pub sw_vcs_commit: u32,
29430 #[doc = "Node name string. For example, \"sapog.px4.io\"."]
29431 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29432 pub name: [u8; 80],
29433 #[doc = "Hardware major version number."]
29434 pub hw_version_major: u8,
29435 #[doc = "Hardware minor version number."]
29436 pub hw_version_minor: u8,
29437 #[doc = "Hardware unique 128-bit ID."]
29438 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29439 pub hw_unique_id: [u8; 16],
29440 #[doc = "Software major version number."]
29441 pub sw_version_major: u8,
29442 #[doc = "Software minor version number."]
29443 pub sw_version_minor: u8,
29444}
29445impl UAVCAN_NODE_INFO_DATA {
29446 pub const ENCODED_LEN: usize = 116usize;
29447 pub const DEFAULT: Self = Self {
29448 time_usec: 0_u64,
29449 uptime_sec: 0_u32,
29450 sw_vcs_commit: 0_u32,
29451 name: [0_u8; 80usize],
29452 hw_version_major: 0_u8,
29453 hw_version_minor: 0_u8,
29454 hw_unique_id: [0_u8; 16usize],
29455 sw_version_major: 0_u8,
29456 sw_version_minor: 0_u8,
29457 };
29458 #[cfg(feature = "arbitrary")]
29459 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29460 use arbitrary::{Arbitrary, Unstructured};
29461 let mut buf = [0u8; 1024];
29462 rng.fill_bytes(&mut buf);
29463 let mut unstructured = Unstructured::new(&buf);
29464 Self::arbitrary(&mut unstructured).unwrap_or_default()
29465 }
29466}
29467impl Default for UAVCAN_NODE_INFO_DATA {
29468 fn default() -> Self {
29469 Self::DEFAULT.clone()
29470 }
29471}
29472impl MessageData for UAVCAN_NODE_INFO_DATA {
29473 type Message = MavMessage;
29474 const ID: u32 = 311u32;
29475 const NAME: &'static str = "UAVCAN_NODE_INFO";
29476 const EXTRA_CRC: u8 = 95u8;
29477 const ENCODED_LEN: usize = 116usize;
29478 fn deser(
29479 _version: MavlinkVersion,
29480 __input: &[u8],
29481 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29482 let avail_len = __input.len();
29483 let mut payload_buf = [0; Self::ENCODED_LEN];
29484 let mut buf = if avail_len < Self::ENCODED_LEN {
29485 payload_buf[0..avail_len].copy_from_slice(__input);
29486 Bytes::new(&payload_buf)
29487 } else {
29488 Bytes::new(__input)
29489 };
29490 let mut __struct = Self::default();
29491 __struct.time_usec = buf.get_u64_le();
29492 __struct.uptime_sec = buf.get_u32_le();
29493 __struct.sw_vcs_commit = buf.get_u32_le();
29494 for v in &mut __struct.name {
29495 let val = buf.get_u8();
29496 *v = val;
29497 }
29498 __struct.hw_version_major = buf.get_u8();
29499 __struct.hw_version_minor = buf.get_u8();
29500 for v in &mut __struct.hw_unique_id {
29501 let val = buf.get_u8();
29502 *v = val;
29503 }
29504 __struct.sw_version_major = buf.get_u8();
29505 __struct.sw_version_minor = buf.get_u8();
29506 Ok(__struct)
29507 }
29508 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29509 let mut __tmp = BytesMut::new(bytes);
29510 #[allow(clippy::absurd_extreme_comparisons)]
29511 #[allow(unused_comparisons)]
29512 if __tmp.remaining() < Self::ENCODED_LEN {
29513 panic!(
29514 "buffer is too small (need {} bytes, but got {})",
29515 Self::ENCODED_LEN,
29516 __tmp.remaining(),
29517 )
29518 }
29519 __tmp.put_u64_le(self.time_usec);
29520 __tmp.put_u32_le(self.uptime_sec);
29521 __tmp.put_u32_le(self.sw_vcs_commit);
29522 for val in &self.name {
29523 __tmp.put_u8(*val);
29524 }
29525 __tmp.put_u8(self.hw_version_major);
29526 __tmp.put_u8(self.hw_version_minor);
29527 for val in &self.hw_unique_id {
29528 __tmp.put_u8(*val);
29529 }
29530 __tmp.put_u8(self.sw_version_major);
29531 __tmp.put_u8(self.sw_version_minor);
29532 if matches!(version, MavlinkVersion::V2) {
29533 let len = __tmp.len();
29534 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29535 } else {
29536 __tmp.len()
29537 }
29538 }
29539}
29540#[doc = "id: 310"]
29541#[doc = "General status information of an UAVCAN node. Please refer to the definition of the UAVCAN message \"uavcan.protocol.NodeStatus\" for the background information. The UAVCAN specification is available at <http://uavcan.org>."]
29542#[derive(Debug, Clone, PartialEq)]
29543#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29544#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29545pub struct UAVCAN_NODE_STATUS_DATA {
29546 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
29547 pub time_usec: u64,
29548 #[doc = "Time since the start-up of the node."]
29549 pub uptime_sec: u32,
29550 #[doc = "Vendor-specific status information."]
29551 pub vendor_specific_status_code: u16,
29552 #[doc = "Generalized node health status."]
29553 pub health: UavcanNodeHealth,
29554 #[doc = "Generalized operating mode."]
29555 pub mode: UavcanNodeMode,
29556 #[doc = "Not used currently."]
29557 pub sub_mode: u8,
29558}
29559impl UAVCAN_NODE_STATUS_DATA {
29560 pub const ENCODED_LEN: usize = 17usize;
29561 pub const DEFAULT: Self = Self {
29562 time_usec: 0_u64,
29563 uptime_sec: 0_u32,
29564 vendor_specific_status_code: 0_u16,
29565 health: UavcanNodeHealth::DEFAULT,
29566 mode: UavcanNodeMode::DEFAULT,
29567 sub_mode: 0_u8,
29568 };
29569 #[cfg(feature = "arbitrary")]
29570 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29571 use arbitrary::{Arbitrary, Unstructured};
29572 let mut buf = [0u8; 1024];
29573 rng.fill_bytes(&mut buf);
29574 let mut unstructured = Unstructured::new(&buf);
29575 Self::arbitrary(&mut unstructured).unwrap_or_default()
29576 }
29577}
29578impl Default for UAVCAN_NODE_STATUS_DATA {
29579 fn default() -> Self {
29580 Self::DEFAULT.clone()
29581 }
29582}
29583impl MessageData for UAVCAN_NODE_STATUS_DATA {
29584 type Message = MavMessage;
29585 const ID: u32 = 310u32;
29586 const NAME: &'static str = "UAVCAN_NODE_STATUS";
29587 const EXTRA_CRC: u8 = 28u8;
29588 const ENCODED_LEN: usize = 17usize;
29589 fn deser(
29590 _version: MavlinkVersion,
29591 __input: &[u8],
29592 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29593 let avail_len = __input.len();
29594 let mut payload_buf = [0; Self::ENCODED_LEN];
29595 let mut buf = if avail_len < Self::ENCODED_LEN {
29596 payload_buf[0..avail_len].copy_from_slice(__input);
29597 Bytes::new(&payload_buf)
29598 } else {
29599 Bytes::new(__input)
29600 };
29601 let mut __struct = Self::default();
29602 __struct.time_usec = buf.get_u64_le();
29603 __struct.uptime_sec = buf.get_u32_le();
29604 __struct.vendor_specific_status_code = buf.get_u16_le();
29605 let tmp = buf.get_u8();
29606 __struct.health =
29607 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29608 enum_type: "UavcanNodeHealth",
29609 value: tmp as u32,
29610 })?;
29611 let tmp = buf.get_u8();
29612 __struct.mode =
29613 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29614 enum_type: "UavcanNodeMode",
29615 value: tmp as u32,
29616 })?;
29617 __struct.sub_mode = buf.get_u8();
29618 Ok(__struct)
29619 }
29620 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29621 let mut __tmp = BytesMut::new(bytes);
29622 #[allow(clippy::absurd_extreme_comparisons)]
29623 #[allow(unused_comparisons)]
29624 if __tmp.remaining() < Self::ENCODED_LEN {
29625 panic!(
29626 "buffer is too small (need {} bytes, but got {})",
29627 Self::ENCODED_LEN,
29628 __tmp.remaining(),
29629 )
29630 }
29631 __tmp.put_u64_le(self.time_usec);
29632 __tmp.put_u32_le(self.uptime_sec);
29633 __tmp.put_u16_le(self.vendor_specific_status_code);
29634 __tmp.put_u8(self.health as u8);
29635 __tmp.put_u8(self.mode as u8);
29636 __tmp.put_u8(self.sub_mode);
29637 if matches!(version, MavlinkVersion::V2) {
29638 let len = __tmp.len();
29639 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29640 } else {
29641 __tmp.len()
29642 }
29643 }
29644}
29645#[doc = "id: 10006"]
29646#[doc = "Request messages."]
29647#[derive(Debug, Clone, PartialEq)]
29648#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29649#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29650pub struct UAVIONIX_ADSB_GET_DATA {
29651 #[doc = "Message ID to request. Supports any message in this 10000-10099 range"]
29652 pub ReqMessageId: u32,
29653}
29654impl UAVIONIX_ADSB_GET_DATA {
29655 pub const ENCODED_LEN: usize = 4usize;
29656 pub const DEFAULT: Self = Self {
29657 ReqMessageId: 0_u32,
29658 };
29659 #[cfg(feature = "arbitrary")]
29660 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29661 use arbitrary::{Arbitrary, Unstructured};
29662 let mut buf = [0u8; 1024];
29663 rng.fill_bytes(&mut buf);
29664 let mut unstructured = Unstructured::new(&buf);
29665 Self::arbitrary(&mut unstructured).unwrap_or_default()
29666 }
29667}
29668impl Default for UAVIONIX_ADSB_GET_DATA {
29669 fn default() -> Self {
29670 Self::DEFAULT.clone()
29671 }
29672}
29673impl MessageData for UAVIONIX_ADSB_GET_DATA {
29674 type Message = MavMessage;
29675 const ID: u32 = 10006u32;
29676 const NAME: &'static str = "UAVIONIX_ADSB_GET";
29677 const EXTRA_CRC: u8 = 193u8;
29678 const ENCODED_LEN: usize = 4usize;
29679 fn deser(
29680 _version: MavlinkVersion,
29681 __input: &[u8],
29682 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29683 let avail_len = __input.len();
29684 let mut payload_buf = [0; Self::ENCODED_LEN];
29685 let mut buf = if avail_len < Self::ENCODED_LEN {
29686 payload_buf[0..avail_len].copy_from_slice(__input);
29687 Bytes::new(&payload_buf)
29688 } else {
29689 Bytes::new(__input)
29690 };
29691 let mut __struct = Self::default();
29692 __struct.ReqMessageId = buf.get_u32_le();
29693 Ok(__struct)
29694 }
29695 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29696 let mut __tmp = BytesMut::new(bytes);
29697 #[allow(clippy::absurd_extreme_comparisons)]
29698 #[allow(unused_comparisons)]
29699 if __tmp.remaining() < Self::ENCODED_LEN {
29700 panic!(
29701 "buffer is too small (need {} bytes, but got {})",
29702 Self::ENCODED_LEN,
29703 __tmp.remaining(),
29704 )
29705 }
29706 __tmp.put_u32_le(self.ReqMessageId);
29707 if matches!(version, MavlinkVersion::V2) {
29708 let len = __tmp.len();
29709 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29710 } else {
29711 __tmp.len()
29712 }
29713 }
29714}
29715#[doc = "id: 10001"]
29716#[doc = "Static data to configure the ADS-B transponder (send within 10 sec of a POR and every 10 sec thereafter)."]
29717#[derive(Debug, Clone, PartialEq)]
29718#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29719#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29720pub struct UAVIONIX_ADSB_OUT_CFG_DATA {
29721 #[doc = "Vehicle address (24 bit)"]
29722 pub ICAO: u32,
29723 #[doc = "Aircraft stall speed in cm/s"]
29724 pub stallSpeed: u16,
29725 #[doc = "Vehicle identifier (8 characters, null terminated, valid characters are A-Z, 0-9, \" \" only)"]
29726 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29727 pub callsign: [u8; 9],
29728 #[doc = "Transmitting vehicle type. See ADSB_EMITTER_TYPE enum"]
29729 pub emitterType: AdsbEmitterType,
29730 #[doc = "Aircraft length and width encoding (table 2-35 of DO-282B)"]
29731 pub aircraftSize: UavionixAdsbOutCfgAircraftSize,
29732 #[doc = "GPS antenna lateral offset (table 2-36 of DO-282B)"]
29733 pub gpsOffsetLat: UavionixAdsbOutCfgGpsOffsetLat,
29734 #[doc = "GPS antenna longitudinal offset from nose [if non-zero, take position (in meters) divide by 2 and add one] (table 2-37 DO-282B)"]
29735 pub gpsOffsetLon: UavionixAdsbOutCfgGpsOffsetLon,
29736 #[doc = "ADS-B transponder reciever and transmit enable flags"]
29737 pub rfSelect: UavionixAdsbOutRfSelect,
29738}
29739impl UAVIONIX_ADSB_OUT_CFG_DATA {
29740 pub const ENCODED_LEN: usize = 20usize;
29741 pub const DEFAULT: Self = Self {
29742 ICAO: 0_u32,
29743 stallSpeed: 0_u16,
29744 callsign: [0_u8; 9usize],
29745 emitterType: AdsbEmitterType::DEFAULT,
29746 aircraftSize: UavionixAdsbOutCfgAircraftSize::DEFAULT,
29747 gpsOffsetLat: UavionixAdsbOutCfgGpsOffsetLat::DEFAULT,
29748 gpsOffsetLon: UavionixAdsbOutCfgGpsOffsetLon::DEFAULT,
29749 rfSelect: UavionixAdsbOutRfSelect::DEFAULT,
29750 };
29751 #[cfg(feature = "arbitrary")]
29752 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29753 use arbitrary::{Arbitrary, Unstructured};
29754 let mut buf = [0u8; 1024];
29755 rng.fill_bytes(&mut buf);
29756 let mut unstructured = Unstructured::new(&buf);
29757 Self::arbitrary(&mut unstructured).unwrap_or_default()
29758 }
29759}
29760impl Default for UAVIONIX_ADSB_OUT_CFG_DATA {
29761 fn default() -> Self {
29762 Self::DEFAULT.clone()
29763 }
29764}
29765impl MessageData for UAVIONIX_ADSB_OUT_CFG_DATA {
29766 type Message = MavMessage;
29767 const ID: u32 = 10001u32;
29768 const NAME: &'static str = "UAVIONIX_ADSB_OUT_CFG";
29769 const EXTRA_CRC: u8 = 209u8;
29770 const ENCODED_LEN: usize = 20usize;
29771 fn deser(
29772 _version: MavlinkVersion,
29773 __input: &[u8],
29774 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29775 let avail_len = __input.len();
29776 let mut payload_buf = [0; Self::ENCODED_LEN];
29777 let mut buf = if avail_len < Self::ENCODED_LEN {
29778 payload_buf[0..avail_len].copy_from_slice(__input);
29779 Bytes::new(&payload_buf)
29780 } else {
29781 Bytes::new(__input)
29782 };
29783 let mut __struct = Self::default();
29784 __struct.ICAO = buf.get_u32_le();
29785 __struct.stallSpeed = buf.get_u16_le();
29786 for v in &mut __struct.callsign {
29787 let val = buf.get_u8();
29788 *v = val;
29789 }
29790 let tmp = buf.get_u8();
29791 __struct.emitterType =
29792 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29793 enum_type: "AdsbEmitterType",
29794 value: tmp as u32,
29795 })?;
29796 let tmp = buf.get_u8();
29797 __struct.aircraftSize =
29798 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29799 enum_type: "UavionixAdsbOutCfgAircraftSize",
29800 value: tmp as u32,
29801 })?;
29802 let tmp = buf.get_u8();
29803 __struct.gpsOffsetLat =
29804 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29805 enum_type: "UavionixAdsbOutCfgGpsOffsetLat",
29806 value: tmp as u32,
29807 })?;
29808 let tmp = buf.get_u8();
29809 __struct.gpsOffsetLon =
29810 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29811 enum_type: "UavionixAdsbOutCfgGpsOffsetLon",
29812 value: tmp as u32,
29813 })?;
29814 let tmp = buf.get_u8();
29815 __struct.rfSelect = UavionixAdsbOutRfSelect::from_bits(
29816 tmp & UavionixAdsbOutRfSelect::all().bits(),
29817 )
29818 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
29819 flag_type: "UavionixAdsbOutRfSelect",
29820 value: tmp as u32,
29821 })?;
29822 Ok(__struct)
29823 }
29824 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29825 let mut __tmp = BytesMut::new(bytes);
29826 #[allow(clippy::absurd_extreme_comparisons)]
29827 #[allow(unused_comparisons)]
29828 if __tmp.remaining() < Self::ENCODED_LEN {
29829 panic!(
29830 "buffer is too small (need {} bytes, but got {})",
29831 Self::ENCODED_LEN,
29832 __tmp.remaining(),
29833 )
29834 }
29835 __tmp.put_u32_le(self.ICAO);
29836 __tmp.put_u16_le(self.stallSpeed);
29837 for val in &self.callsign {
29838 __tmp.put_u8(*val);
29839 }
29840 __tmp.put_u8(self.emitterType as u8);
29841 __tmp.put_u8(self.aircraftSize as u8);
29842 __tmp.put_u8(self.gpsOffsetLat as u8);
29843 __tmp.put_u8(self.gpsOffsetLon as u8);
29844 __tmp.put_u8(self.rfSelect.bits());
29845 if matches!(version, MavlinkVersion::V2) {
29846 let len = __tmp.len();
29847 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29848 } else {
29849 __tmp.len()
29850 }
29851 }
29852}
29853#[doc = "id: 10005"]
29854#[doc = "Flight Identification for ADSB-Out vehicles."]
29855#[derive(Debug, Clone, PartialEq)]
29856#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29857#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29858pub struct UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA {
29859 #[doc = "Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable. Reflects Control message setting. This is null-terminated."]
29860 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29861 pub flight_id: [u8; 9],
29862}
29863impl UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA {
29864 pub const ENCODED_LEN: usize = 9usize;
29865 pub const DEFAULT: Self = Self {
29866 flight_id: [0_u8; 9usize],
29867 };
29868 #[cfg(feature = "arbitrary")]
29869 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29870 use arbitrary::{Arbitrary, Unstructured};
29871 let mut buf = [0u8; 1024];
29872 rng.fill_bytes(&mut buf);
29873 let mut unstructured = Unstructured::new(&buf);
29874 Self::arbitrary(&mut unstructured).unwrap_or_default()
29875 }
29876}
29877impl Default for UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA {
29878 fn default() -> Self {
29879 Self::DEFAULT.clone()
29880 }
29881}
29882impl MessageData for UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA {
29883 type Message = MavMessage;
29884 const ID: u32 = 10005u32;
29885 const NAME: &'static str = "UAVIONIX_ADSB_OUT_CFG_FLIGHTID";
29886 const EXTRA_CRC: u8 = 103u8;
29887 const ENCODED_LEN: usize = 9usize;
29888 fn deser(
29889 _version: MavlinkVersion,
29890 __input: &[u8],
29891 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29892 let avail_len = __input.len();
29893 let mut payload_buf = [0; Self::ENCODED_LEN];
29894 let mut buf = if avail_len < Self::ENCODED_LEN {
29895 payload_buf[0..avail_len].copy_from_slice(__input);
29896 Bytes::new(&payload_buf)
29897 } else {
29898 Bytes::new(__input)
29899 };
29900 let mut __struct = Self::default();
29901 for v in &mut __struct.flight_id {
29902 let val = buf.get_u8();
29903 *v = val;
29904 }
29905 Ok(__struct)
29906 }
29907 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29908 let mut __tmp = BytesMut::new(bytes);
29909 #[allow(clippy::absurd_extreme_comparisons)]
29910 #[allow(unused_comparisons)]
29911 if __tmp.remaining() < Self::ENCODED_LEN {
29912 panic!(
29913 "buffer is too small (need {} bytes, but got {})",
29914 Self::ENCODED_LEN,
29915 __tmp.remaining(),
29916 )
29917 }
29918 for val in &self.flight_id {
29919 __tmp.put_u8(*val);
29920 }
29921 if matches!(version, MavlinkVersion::V2) {
29922 let len = __tmp.len();
29923 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29924 } else {
29925 __tmp.len()
29926 }
29927 }
29928}
29929#[doc = "id: 10004"]
29930#[doc = "Aircraft Registration."]
29931#[derive(Debug, Clone, PartialEq)]
29932#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29933#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29934pub struct UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA {
29935 #[doc = "Aircraft Registration (ASCII string A-Z, 0-9 only), e.g. \"N8644B \". Trailing spaces (0x20) only. This is null-terminated."]
29936 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29937 pub registration: [u8; 9],
29938}
29939impl UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA {
29940 pub const ENCODED_LEN: usize = 9usize;
29941 pub const DEFAULT: Self = Self {
29942 registration: [0_u8; 9usize],
29943 };
29944 #[cfg(feature = "arbitrary")]
29945 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29946 use arbitrary::{Arbitrary, Unstructured};
29947 let mut buf = [0u8; 1024];
29948 rng.fill_bytes(&mut buf);
29949 let mut unstructured = Unstructured::new(&buf);
29950 Self::arbitrary(&mut unstructured).unwrap_or_default()
29951 }
29952}
29953impl Default for UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA {
29954 fn default() -> Self {
29955 Self::DEFAULT.clone()
29956 }
29957}
29958impl MessageData for UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA {
29959 type Message = MavMessage;
29960 const ID: u32 = 10004u32;
29961 const NAME: &'static str = "UAVIONIX_ADSB_OUT_CFG_REGISTRATION";
29962 const EXTRA_CRC: u8 = 133u8;
29963 const ENCODED_LEN: usize = 9usize;
29964 fn deser(
29965 _version: MavlinkVersion,
29966 __input: &[u8],
29967 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29968 let avail_len = __input.len();
29969 let mut payload_buf = [0; Self::ENCODED_LEN];
29970 let mut buf = if avail_len < Self::ENCODED_LEN {
29971 payload_buf[0..avail_len].copy_from_slice(__input);
29972 Bytes::new(&payload_buf)
29973 } else {
29974 Bytes::new(__input)
29975 };
29976 let mut __struct = Self::default();
29977 for v in &mut __struct.registration {
29978 let val = buf.get_u8();
29979 *v = val;
29980 }
29981 Ok(__struct)
29982 }
29983 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29984 let mut __tmp = BytesMut::new(bytes);
29985 #[allow(clippy::absurd_extreme_comparisons)]
29986 #[allow(unused_comparisons)]
29987 if __tmp.remaining() < Self::ENCODED_LEN {
29988 panic!(
29989 "buffer is too small (need {} bytes, but got {})",
29990 Self::ENCODED_LEN,
29991 __tmp.remaining(),
29992 )
29993 }
29994 for val in &self.registration {
29995 __tmp.put_u8(*val);
29996 }
29997 if matches!(version, MavlinkVersion::V2) {
29998 let len = __tmp.len();
29999 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30000 } else {
30001 __tmp.len()
30002 }
30003 }
30004}
30005#[doc = "id: 10007"]
30006#[doc = "Control message with all data sent in UCP control message."]
30007#[derive(Debug, Clone, PartialEq)]
30008#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30009#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30010pub struct UAVIONIX_ADSB_OUT_CONTROL_DATA {
30011 #[doc = "Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX"]
30012 pub baroAltMSL: i32,
30013 #[doc = "Mode A code (typically 1200 [0x04B0] for VFR)"]
30014 pub squawk: u16,
30015 #[doc = "ADS-B transponder control state flags"]
30016 pub state: UavionixAdsbOutControlState,
30017 #[doc = "Emergency status"]
30018 pub emergencyStatus: UavionixAdsbEmergencyStatus,
30019 #[doc = "Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable."]
30020 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30021 pub flight_id: [u8; 8],
30022 #[doc = "X-Bit enable (military transponders only)"]
30023 pub x_bit: UavionixAdsbXbit,
30024}
30025impl UAVIONIX_ADSB_OUT_CONTROL_DATA {
30026 pub const ENCODED_LEN: usize = 17usize;
30027 pub const DEFAULT: Self = Self {
30028 baroAltMSL: 0_i32,
30029 squawk: 0_u16,
30030 state: UavionixAdsbOutControlState::DEFAULT,
30031 emergencyStatus: UavionixAdsbEmergencyStatus::DEFAULT,
30032 flight_id: [0_u8; 8usize],
30033 x_bit: UavionixAdsbXbit::DEFAULT,
30034 };
30035 #[cfg(feature = "arbitrary")]
30036 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30037 use arbitrary::{Arbitrary, Unstructured};
30038 let mut buf = [0u8; 1024];
30039 rng.fill_bytes(&mut buf);
30040 let mut unstructured = Unstructured::new(&buf);
30041 Self::arbitrary(&mut unstructured).unwrap_or_default()
30042 }
30043}
30044impl Default for UAVIONIX_ADSB_OUT_CONTROL_DATA {
30045 fn default() -> Self {
30046 Self::DEFAULT.clone()
30047 }
30048}
30049impl MessageData for UAVIONIX_ADSB_OUT_CONTROL_DATA {
30050 type Message = MavMessage;
30051 const ID: u32 = 10007u32;
30052 const NAME: &'static str = "UAVIONIX_ADSB_OUT_CONTROL";
30053 const EXTRA_CRC: u8 = 71u8;
30054 const ENCODED_LEN: usize = 17usize;
30055 fn deser(
30056 _version: MavlinkVersion,
30057 __input: &[u8],
30058 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30059 let avail_len = __input.len();
30060 let mut payload_buf = [0; Self::ENCODED_LEN];
30061 let mut buf = if avail_len < Self::ENCODED_LEN {
30062 payload_buf[0..avail_len].copy_from_slice(__input);
30063 Bytes::new(&payload_buf)
30064 } else {
30065 Bytes::new(__input)
30066 };
30067 let mut __struct = Self::default();
30068 __struct.baroAltMSL = buf.get_i32_le();
30069 __struct.squawk = buf.get_u16_le();
30070 let tmp = buf.get_u8();
30071 __struct.state =
30072 UavionixAdsbOutControlState::from_bits(tmp & UavionixAdsbOutControlState::all().bits())
30073 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
30074 flag_type: "UavionixAdsbOutControlState",
30075 value: tmp as u32,
30076 })?;
30077 let tmp = buf.get_u8();
30078 __struct.emergencyStatus =
30079 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30080 enum_type: "UavionixAdsbEmergencyStatus",
30081 value: tmp as u32,
30082 })?;
30083 for v in &mut __struct.flight_id {
30084 let val = buf.get_u8();
30085 *v = val;
30086 }
30087 let tmp = buf.get_u8();
30088 __struct.x_bit = UavionixAdsbXbit::from_bits(tmp & UavionixAdsbXbit::all().bits()).ok_or(
30089 ::mavlink_core::error::ParserError::InvalidFlag {
30090 flag_type: "UavionixAdsbXbit",
30091 value: tmp as u32,
30092 },
30093 )?;
30094 Ok(__struct)
30095 }
30096 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30097 let mut __tmp = BytesMut::new(bytes);
30098 #[allow(clippy::absurd_extreme_comparisons)]
30099 #[allow(unused_comparisons)]
30100 if __tmp.remaining() < Self::ENCODED_LEN {
30101 panic!(
30102 "buffer is too small (need {} bytes, but got {})",
30103 Self::ENCODED_LEN,
30104 __tmp.remaining(),
30105 )
30106 }
30107 __tmp.put_i32_le(self.baroAltMSL);
30108 __tmp.put_u16_le(self.squawk);
30109 __tmp.put_u8(self.state.bits());
30110 __tmp.put_u8(self.emergencyStatus as u8);
30111 for val in &self.flight_id {
30112 __tmp.put_u8(*val);
30113 }
30114 __tmp.put_u8(self.x_bit.bits());
30115 if matches!(version, MavlinkVersion::V2) {
30116 let len = __tmp.len();
30117 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30118 } else {
30119 __tmp.len()
30120 }
30121 }
30122}
30123#[doc = "id: 10002"]
30124#[doc = "Dynamic data used to generate ADS-B out transponder data (send at 5Hz)."]
30125#[derive(Debug, Clone, PartialEq)]
30126#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30127#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30128pub struct UAVIONIX_ADSB_OUT_DYNAMIC_DATA {
30129 #[doc = "UTC time in seconds since GPS epoch (Jan 6, 1980). If unknown set to UINT32_MAX"]
30130 pub utcTime: u32,
30131 #[doc = "Latitude WGS84 (deg * 1E7). If unknown set to INT32_MAX"]
30132 pub gpsLat: i32,
30133 #[doc = "Longitude WGS84 (deg * 1E7). If unknown set to INT32_MAX"]
30134 pub gpsLon: i32,
30135 #[doc = "Altitude (WGS84). UP +ve. If unknown set to INT32_MAX"]
30136 pub gpsAlt: i32,
30137 #[doc = "Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX"]
30138 pub baroAltMSL: i32,
30139 #[doc = "Horizontal accuracy in mm (m * 1E-3). If unknown set to UINT32_MAX"]
30140 pub accuracyHor: u32,
30141 #[doc = "Vertical accuracy in cm. If unknown set to UINT16_MAX"]
30142 pub accuracyVert: u16,
30143 #[doc = "Velocity accuracy in mm/s (m * 1E-3). If unknown set to UINT16_MAX"]
30144 pub accuracyVel: u16,
30145 #[doc = "GPS vertical speed in cm/s. If unknown set to INT16_MAX"]
30146 pub velVert: i16,
30147 #[doc = "North-South velocity over ground in cm/s North +ve. If unknown set to INT16_MAX"]
30148 pub velNS: i16,
30149 #[doc = "East-West velocity over ground in cm/s East +ve. If unknown set to INT16_MAX"]
30150 pub VelEW: i16,
30151 #[doc = "ADS-B transponder dynamic input state flags"]
30152 pub state: UavionixAdsbOutDynamicState,
30153 #[doc = "Mode A code (typically 1200 [0x04B0] for VFR)"]
30154 pub squawk: u16,
30155 #[doc = "0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK"]
30156 pub gpsFix: UavionixAdsbOutDynamicGpsFix,
30157 #[doc = "Number of satellites visible. If unknown set to UINT8_MAX"]
30158 pub numSats: u8,
30159 #[doc = "Emergency status"]
30160 pub emergencyStatus: UavionixAdsbEmergencyStatus,
30161}
30162impl UAVIONIX_ADSB_OUT_DYNAMIC_DATA {
30163 pub const ENCODED_LEN: usize = 41usize;
30164 pub const DEFAULT: Self = Self {
30165 utcTime: 0_u32,
30166 gpsLat: 0_i32,
30167 gpsLon: 0_i32,
30168 gpsAlt: 0_i32,
30169 baroAltMSL: 0_i32,
30170 accuracyHor: 0_u32,
30171 accuracyVert: 0_u16,
30172 accuracyVel: 0_u16,
30173 velVert: 0_i16,
30174 velNS: 0_i16,
30175 VelEW: 0_i16,
30176 state: UavionixAdsbOutDynamicState::DEFAULT,
30177 squawk: 0_u16,
30178 gpsFix: UavionixAdsbOutDynamicGpsFix::DEFAULT,
30179 numSats: 0_u8,
30180 emergencyStatus: UavionixAdsbEmergencyStatus::DEFAULT,
30181 };
30182 #[cfg(feature = "arbitrary")]
30183 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30184 use arbitrary::{Arbitrary, Unstructured};
30185 let mut buf = [0u8; 1024];
30186 rng.fill_bytes(&mut buf);
30187 let mut unstructured = Unstructured::new(&buf);
30188 Self::arbitrary(&mut unstructured).unwrap_or_default()
30189 }
30190}
30191impl Default for UAVIONIX_ADSB_OUT_DYNAMIC_DATA {
30192 fn default() -> Self {
30193 Self::DEFAULT.clone()
30194 }
30195}
30196impl MessageData for UAVIONIX_ADSB_OUT_DYNAMIC_DATA {
30197 type Message = MavMessage;
30198 const ID: u32 = 10002u32;
30199 const NAME: &'static str = "UAVIONIX_ADSB_OUT_DYNAMIC";
30200 const EXTRA_CRC: u8 = 186u8;
30201 const ENCODED_LEN: usize = 41usize;
30202 fn deser(
30203 _version: MavlinkVersion,
30204 __input: &[u8],
30205 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30206 let avail_len = __input.len();
30207 let mut payload_buf = [0; Self::ENCODED_LEN];
30208 let mut buf = if avail_len < Self::ENCODED_LEN {
30209 payload_buf[0..avail_len].copy_from_slice(__input);
30210 Bytes::new(&payload_buf)
30211 } else {
30212 Bytes::new(__input)
30213 };
30214 let mut __struct = Self::default();
30215 __struct.utcTime = buf.get_u32_le();
30216 __struct.gpsLat = buf.get_i32_le();
30217 __struct.gpsLon = buf.get_i32_le();
30218 __struct.gpsAlt = buf.get_i32_le();
30219 __struct.baroAltMSL = buf.get_i32_le();
30220 __struct.accuracyHor = buf.get_u32_le();
30221 __struct.accuracyVert = buf.get_u16_le();
30222 __struct.accuracyVel = buf.get_u16_le();
30223 __struct.velVert = buf.get_i16_le();
30224 __struct.velNS = buf.get_i16_le();
30225 __struct.VelEW = buf.get_i16_le();
30226 let tmp = buf.get_u16_le();
30227 __struct.state =
30228 UavionixAdsbOutDynamicState::from_bits(tmp & UavionixAdsbOutDynamicState::all().bits())
30229 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
30230 flag_type: "UavionixAdsbOutDynamicState",
30231 value: tmp as u32,
30232 })?;
30233 __struct.squawk = buf.get_u16_le();
30234 let tmp = buf.get_u8();
30235 __struct.gpsFix =
30236 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30237 enum_type: "UavionixAdsbOutDynamicGpsFix",
30238 value: tmp as u32,
30239 })?;
30240 __struct.numSats = buf.get_u8();
30241 let tmp = buf.get_u8();
30242 __struct.emergencyStatus =
30243 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30244 enum_type: "UavionixAdsbEmergencyStatus",
30245 value: tmp as u32,
30246 })?;
30247 Ok(__struct)
30248 }
30249 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30250 let mut __tmp = BytesMut::new(bytes);
30251 #[allow(clippy::absurd_extreme_comparisons)]
30252 #[allow(unused_comparisons)]
30253 if __tmp.remaining() < Self::ENCODED_LEN {
30254 panic!(
30255 "buffer is too small (need {} bytes, but got {})",
30256 Self::ENCODED_LEN,
30257 __tmp.remaining(),
30258 )
30259 }
30260 __tmp.put_u32_le(self.utcTime);
30261 __tmp.put_i32_le(self.gpsLat);
30262 __tmp.put_i32_le(self.gpsLon);
30263 __tmp.put_i32_le(self.gpsAlt);
30264 __tmp.put_i32_le(self.baroAltMSL);
30265 __tmp.put_u32_le(self.accuracyHor);
30266 __tmp.put_u16_le(self.accuracyVert);
30267 __tmp.put_u16_le(self.accuracyVel);
30268 __tmp.put_i16_le(self.velVert);
30269 __tmp.put_i16_le(self.velNS);
30270 __tmp.put_i16_le(self.VelEW);
30271 __tmp.put_u16_le(self.state.bits());
30272 __tmp.put_u16_le(self.squawk);
30273 __tmp.put_u8(self.gpsFix as u8);
30274 __tmp.put_u8(self.numSats);
30275 __tmp.put_u8(self.emergencyStatus as u8);
30276 if matches!(version, MavlinkVersion::V2) {
30277 let len = __tmp.len();
30278 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30279 } else {
30280 __tmp.len()
30281 }
30282 }
30283}
30284#[doc = "id: 10008"]
30285#[doc = "Status message with information from UCP Heartbeat and Status messages."]
30286#[derive(Debug, Clone, PartialEq)]
30287#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30288#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30289pub struct UAVIONIX_ADSB_OUT_STATUS_DATA {
30290 #[doc = "Mode A code (typically 1200 [0x04B0] for VFR)"]
30291 pub squawk: u16,
30292 #[doc = "ADS-B transponder status state flags"]
30293 pub state: UavionixAdsbOutStatusState,
30294 #[doc = "Integrity and Accuracy of traffic reported as a 4-bit value for each field (NACp 7:4, NIC 3:0) and encoded by Containment Radius (HPL) and Estimated Position Uncertainty (HFOM), respectively"]
30295 pub NIC_NACp: UavionixAdsbOutStatusNicNacp,
30296 #[doc = "Board temperature in C"]
30297 pub boardTemp: u8,
30298 #[doc = "ADS-B transponder fault flags"]
30299 pub fault: UavionixAdsbOutStatusFault,
30300 #[doc = "Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable."]
30301 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30302 pub flight_id: [u8; 8],
30303}
30304impl UAVIONIX_ADSB_OUT_STATUS_DATA {
30305 pub const ENCODED_LEN: usize = 14usize;
30306 pub const DEFAULT: Self = Self {
30307 squawk: 0_u16,
30308 state: UavionixAdsbOutStatusState::DEFAULT,
30309 NIC_NACp: UavionixAdsbOutStatusNicNacp::DEFAULT,
30310 boardTemp: 0_u8,
30311 fault: UavionixAdsbOutStatusFault::DEFAULT,
30312 flight_id: [0_u8; 8usize],
30313 };
30314 #[cfg(feature = "arbitrary")]
30315 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30316 use arbitrary::{Arbitrary, Unstructured};
30317 let mut buf = [0u8; 1024];
30318 rng.fill_bytes(&mut buf);
30319 let mut unstructured = Unstructured::new(&buf);
30320 Self::arbitrary(&mut unstructured).unwrap_or_default()
30321 }
30322}
30323impl Default for UAVIONIX_ADSB_OUT_STATUS_DATA {
30324 fn default() -> Self {
30325 Self::DEFAULT.clone()
30326 }
30327}
30328impl MessageData for UAVIONIX_ADSB_OUT_STATUS_DATA {
30329 type Message = MavMessage;
30330 const ID: u32 = 10008u32;
30331 const NAME: &'static str = "UAVIONIX_ADSB_OUT_STATUS";
30332 const EXTRA_CRC: u8 = 240u8;
30333 const ENCODED_LEN: usize = 14usize;
30334 fn deser(
30335 _version: MavlinkVersion,
30336 __input: &[u8],
30337 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30338 let avail_len = __input.len();
30339 let mut payload_buf = [0; Self::ENCODED_LEN];
30340 let mut buf = if avail_len < Self::ENCODED_LEN {
30341 payload_buf[0..avail_len].copy_from_slice(__input);
30342 Bytes::new(&payload_buf)
30343 } else {
30344 Bytes::new(__input)
30345 };
30346 let mut __struct = Self::default();
30347 __struct.squawk = buf.get_u16_le();
30348 let tmp = buf.get_u8();
30349 __struct.state =
30350 UavionixAdsbOutStatusState::from_bits(tmp & UavionixAdsbOutStatusState::all().bits())
30351 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
30352 flag_type: "UavionixAdsbOutStatusState",
30353 value: tmp as u32,
30354 })?;
30355 let tmp = buf.get_u8();
30356 __struct.NIC_NACp =
30357 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30358 enum_type: "UavionixAdsbOutStatusNicNacp",
30359 value: tmp as u32,
30360 })?;
30361 __struct.boardTemp = buf.get_u8();
30362 let tmp = buf.get_u8();
30363 __struct.fault =
30364 UavionixAdsbOutStatusFault::from_bits(tmp & UavionixAdsbOutStatusFault::all().bits())
30365 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
30366 flag_type: "UavionixAdsbOutStatusFault",
30367 value: tmp as u32,
30368 })?;
30369 for v in &mut __struct.flight_id {
30370 let val = buf.get_u8();
30371 *v = val;
30372 }
30373 Ok(__struct)
30374 }
30375 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30376 let mut __tmp = BytesMut::new(bytes);
30377 #[allow(clippy::absurd_extreme_comparisons)]
30378 #[allow(unused_comparisons)]
30379 if __tmp.remaining() < Self::ENCODED_LEN {
30380 panic!(
30381 "buffer is too small (need {} bytes, but got {})",
30382 Self::ENCODED_LEN,
30383 __tmp.remaining(),
30384 )
30385 }
30386 __tmp.put_u16_le(self.squawk);
30387 __tmp.put_u8(self.state.bits());
30388 __tmp.put_u8(self.NIC_NACp as u8);
30389 __tmp.put_u8(self.boardTemp);
30390 __tmp.put_u8(self.fault.bits());
30391 for val in &self.flight_id {
30392 __tmp.put_u8(*val);
30393 }
30394 if matches!(version, MavlinkVersion::V2) {
30395 let len = __tmp.len();
30396 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30397 } else {
30398 __tmp.len()
30399 }
30400 }
30401}
30402#[doc = "id: 10003"]
30403#[doc = "Transceiver heartbeat with health report (updated every 10s)."]
30404#[derive(Debug, Clone, PartialEq)]
30405#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30406#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30407pub struct UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA {
30408 #[doc = "ADS-B transponder messages"]
30409 pub rfHealth: UavionixAdsbRfHealth,
30410}
30411impl UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA {
30412 pub const ENCODED_LEN: usize = 1usize;
30413 pub const DEFAULT: Self = Self {
30414 rfHealth: UavionixAdsbRfHealth::DEFAULT,
30415 };
30416 #[cfg(feature = "arbitrary")]
30417 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30418 use arbitrary::{Arbitrary, Unstructured};
30419 let mut buf = [0u8; 1024];
30420 rng.fill_bytes(&mut buf);
30421 let mut unstructured = Unstructured::new(&buf);
30422 Self::arbitrary(&mut unstructured).unwrap_or_default()
30423 }
30424}
30425impl Default for UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA {
30426 fn default() -> Self {
30427 Self::DEFAULT.clone()
30428 }
30429}
30430impl MessageData for UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA {
30431 type Message = MavMessage;
30432 const ID: u32 = 10003u32;
30433 const NAME: &'static str = "UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT";
30434 const EXTRA_CRC: u8 = 4u8;
30435 const ENCODED_LEN: usize = 1usize;
30436 fn deser(
30437 _version: MavlinkVersion,
30438 __input: &[u8],
30439 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30440 let avail_len = __input.len();
30441 let mut payload_buf = [0; Self::ENCODED_LEN];
30442 let mut buf = if avail_len < Self::ENCODED_LEN {
30443 payload_buf[0..avail_len].copy_from_slice(__input);
30444 Bytes::new(&payload_buf)
30445 } else {
30446 Bytes::new(__input)
30447 };
30448 let mut __struct = Self::default();
30449 let tmp = buf.get_u8();
30450 __struct.rfHealth = UavionixAdsbRfHealth::from_bits(
30451 tmp & UavionixAdsbRfHealth::all().bits(),
30452 )
30453 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
30454 flag_type: "UavionixAdsbRfHealth",
30455 value: tmp as u32,
30456 })?;
30457 Ok(__struct)
30458 }
30459 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30460 let mut __tmp = BytesMut::new(bytes);
30461 #[allow(clippy::absurd_extreme_comparisons)]
30462 #[allow(unused_comparisons)]
30463 if __tmp.remaining() < Self::ENCODED_LEN {
30464 panic!(
30465 "buffer is too small (need {} bytes, but got {})",
30466 Self::ENCODED_LEN,
30467 __tmp.remaining(),
30468 )
30469 }
30470 __tmp.put_u8(self.rfHealth.bits());
30471 if matches!(version, MavlinkVersion::V2) {
30472 let len = __tmp.len();
30473 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30474 } else {
30475 __tmp.len()
30476 }
30477 }
30478}
30479#[doc = "id: 340"]
30480#[doc = "The global position resulting from GPS and sensor fusion."]
30481#[derive(Debug, Clone, PartialEq)]
30482#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30483#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30484pub struct UTM_GLOBAL_POSITION_DATA {
30485 #[doc = "Time of applicability of position (microseconds since UNIX epoch)."]
30486 pub time: u64,
30487 #[doc = "Latitude (WGS84)"]
30488 pub lat: i32,
30489 #[doc = "Longitude (WGS84)"]
30490 pub lon: i32,
30491 #[doc = "Altitude (WGS84)"]
30492 pub alt: i32,
30493 #[doc = "Altitude above ground"]
30494 pub relative_alt: i32,
30495 #[doc = "Next waypoint, latitude (WGS84)"]
30496 pub next_lat: i32,
30497 #[doc = "Next waypoint, longitude (WGS84)"]
30498 pub next_lon: i32,
30499 #[doc = "Next waypoint, altitude (WGS84)"]
30500 pub next_alt: i32,
30501 #[doc = "Ground X speed (latitude, positive north)"]
30502 pub vx: i16,
30503 #[doc = "Ground Y speed (longitude, positive east)"]
30504 pub vy: i16,
30505 #[doc = "Ground Z speed (altitude, positive down)"]
30506 pub vz: i16,
30507 #[doc = "Horizontal position uncertainty (standard deviation)"]
30508 pub h_acc: u16,
30509 #[doc = "Altitude uncertainty (standard deviation)"]
30510 pub v_acc: u16,
30511 #[doc = "Speed uncertainty (standard deviation)"]
30512 pub vel_acc: u16,
30513 #[doc = "Time until next update. Set to 0 if unknown or in data driven mode."]
30514 pub update_rate: u16,
30515 #[doc = "Unique UAS ID."]
30516 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30517 pub uas_id: [u8; 18],
30518 #[doc = "Flight state"]
30519 pub flight_state: UtmFlightState,
30520 #[doc = "Bitwise OR combination of the data available flags."]
30521 pub flags: UtmDataAvailFlags,
30522}
30523impl UTM_GLOBAL_POSITION_DATA {
30524 pub const ENCODED_LEN: usize = 70usize;
30525 pub const DEFAULT: Self = Self {
30526 time: 0_u64,
30527 lat: 0_i32,
30528 lon: 0_i32,
30529 alt: 0_i32,
30530 relative_alt: 0_i32,
30531 next_lat: 0_i32,
30532 next_lon: 0_i32,
30533 next_alt: 0_i32,
30534 vx: 0_i16,
30535 vy: 0_i16,
30536 vz: 0_i16,
30537 h_acc: 0_u16,
30538 v_acc: 0_u16,
30539 vel_acc: 0_u16,
30540 update_rate: 0_u16,
30541 uas_id: [0_u8; 18usize],
30542 flight_state: UtmFlightState::DEFAULT,
30543 flags: UtmDataAvailFlags::DEFAULT,
30544 };
30545 #[cfg(feature = "arbitrary")]
30546 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30547 use arbitrary::{Arbitrary, Unstructured};
30548 let mut buf = [0u8; 1024];
30549 rng.fill_bytes(&mut buf);
30550 let mut unstructured = Unstructured::new(&buf);
30551 Self::arbitrary(&mut unstructured).unwrap_or_default()
30552 }
30553}
30554impl Default for UTM_GLOBAL_POSITION_DATA {
30555 fn default() -> Self {
30556 Self::DEFAULT.clone()
30557 }
30558}
30559impl MessageData for UTM_GLOBAL_POSITION_DATA {
30560 type Message = MavMessage;
30561 const ID: u32 = 340u32;
30562 const NAME: &'static str = "UTM_GLOBAL_POSITION";
30563 const EXTRA_CRC: u8 = 99u8;
30564 const ENCODED_LEN: usize = 70usize;
30565 fn deser(
30566 _version: MavlinkVersion,
30567 __input: &[u8],
30568 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30569 let avail_len = __input.len();
30570 let mut payload_buf = [0; Self::ENCODED_LEN];
30571 let mut buf = if avail_len < Self::ENCODED_LEN {
30572 payload_buf[0..avail_len].copy_from_slice(__input);
30573 Bytes::new(&payload_buf)
30574 } else {
30575 Bytes::new(__input)
30576 };
30577 let mut __struct = Self::default();
30578 __struct.time = buf.get_u64_le();
30579 __struct.lat = buf.get_i32_le();
30580 __struct.lon = buf.get_i32_le();
30581 __struct.alt = buf.get_i32_le();
30582 __struct.relative_alt = buf.get_i32_le();
30583 __struct.next_lat = buf.get_i32_le();
30584 __struct.next_lon = buf.get_i32_le();
30585 __struct.next_alt = buf.get_i32_le();
30586 __struct.vx = buf.get_i16_le();
30587 __struct.vy = buf.get_i16_le();
30588 __struct.vz = buf.get_i16_le();
30589 __struct.h_acc = buf.get_u16_le();
30590 __struct.v_acc = buf.get_u16_le();
30591 __struct.vel_acc = buf.get_u16_le();
30592 __struct.update_rate = buf.get_u16_le();
30593 for v in &mut __struct.uas_id {
30594 let val = buf.get_u8();
30595 *v = val;
30596 }
30597 let tmp = buf.get_u8();
30598 __struct.flight_state =
30599 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30600 enum_type: "UtmFlightState",
30601 value: tmp as u32,
30602 })?;
30603 let tmp = buf.get_u8();
30604 __struct.flags = UtmDataAvailFlags::from_bits(tmp & UtmDataAvailFlags::all().bits())
30605 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
30606 flag_type: "UtmDataAvailFlags",
30607 value: tmp as u32,
30608 })?;
30609 Ok(__struct)
30610 }
30611 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30612 let mut __tmp = BytesMut::new(bytes);
30613 #[allow(clippy::absurd_extreme_comparisons)]
30614 #[allow(unused_comparisons)]
30615 if __tmp.remaining() < Self::ENCODED_LEN {
30616 panic!(
30617 "buffer is too small (need {} bytes, but got {})",
30618 Self::ENCODED_LEN,
30619 __tmp.remaining(),
30620 )
30621 }
30622 __tmp.put_u64_le(self.time);
30623 __tmp.put_i32_le(self.lat);
30624 __tmp.put_i32_le(self.lon);
30625 __tmp.put_i32_le(self.alt);
30626 __tmp.put_i32_le(self.relative_alt);
30627 __tmp.put_i32_le(self.next_lat);
30628 __tmp.put_i32_le(self.next_lon);
30629 __tmp.put_i32_le(self.next_alt);
30630 __tmp.put_i16_le(self.vx);
30631 __tmp.put_i16_le(self.vy);
30632 __tmp.put_i16_le(self.vz);
30633 __tmp.put_u16_le(self.h_acc);
30634 __tmp.put_u16_le(self.v_acc);
30635 __tmp.put_u16_le(self.vel_acc);
30636 __tmp.put_u16_le(self.update_rate);
30637 for val in &self.uas_id {
30638 __tmp.put_u8(*val);
30639 }
30640 __tmp.put_u8(self.flight_state as u8);
30641 __tmp.put_u8(self.flags.bits());
30642 if matches!(version, MavlinkVersion::V2) {
30643 let len = __tmp.len();
30644 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30645 } else {
30646 __tmp.len()
30647 }
30648 }
30649}
30650#[doc = "id: 248"]
30651#[doc = "Message implementing parts of the V2 payload specs in V1 frames for transitional support."]
30652#[derive(Debug, Clone, PartialEq)]
30653#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30654#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30655pub struct V2_EXTENSION_DATA {
30656 #[doc = "A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to <https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml>. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase."]
30657 pub message_type: u16,
30658 #[doc = "Network ID (0 for broadcast)"]
30659 pub target_network: u8,
30660 #[doc = "System ID (0 for broadcast)"]
30661 pub target_system: u8,
30662 #[doc = "Component ID (0 for broadcast)"]
30663 pub target_component: u8,
30664 #[doc = "Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification."]
30665 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30666 pub payload: [u8; 249],
30667}
30668impl V2_EXTENSION_DATA {
30669 pub const ENCODED_LEN: usize = 254usize;
30670 pub const DEFAULT: Self = Self {
30671 message_type: 0_u16,
30672 target_network: 0_u8,
30673 target_system: 0_u8,
30674 target_component: 0_u8,
30675 payload: [0_u8; 249usize],
30676 };
30677 #[cfg(feature = "arbitrary")]
30678 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30679 use arbitrary::{Arbitrary, Unstructured};
30680 let mut buf = [0u8; 1024];
30681 rng.fill_bytes(&mut buf);
30682 let mut unstructured = Unstructured::new(&buf);
30683 Self::arbitrary(&mut unstructured).unwrap_or_default()
30684 }
30685}
30686impl Default for V2_EXTENSION_DATA {
30687 fn default() -> Self {
30688 Self::DEFAULT.clone()
30689 }
30690}
30691impl MessageData for V2_EXTENSION_DATA {
30692 type Message = MavMessage;
30693 const ID: u32 = 248u32;
30694 const NAME: &'static str = "V2_EXTENSION";
30695 const EXTRA_CRC: u8 = 8u8;
30696 const ENCODED_LEN: usize = 254usize;
30697 fn deser(
30698 _version: MavlinkVersion,
30699 __input: &[u8],
30700 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30701 let avail_len = __input.len();
30702 let mut payload_buf = [0; Self::ENCODED_LEN];
30703 let mut buf = if avail_len < Self::ENCODED_LEN {
30704 payload_buf[0..avail_len].copy_from_slice(__input);
30705 Bytes::new(&payload_buf)
30706 } else {
30707 Bytes::new(__input)
30708 };
30709 let mut __struct = Self::default();
30710 __struct.message_type = buf.get_u16_le();
30711 __struct.target_network = buf.get_u8();
30712 __struct.target_system = buf.get_u8();
30713 __struct.target_component = buf.get_u8();
30714 for v in &mut __struct.payload {
30715 let val = buf.get_u8();
30716 *v = val;
30717 }
30718 Ok(__struct)
30719 }
30720 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30721 let mut __tmp = BytesMut::new(bytes);
30722 #[allow(clippy::absurd_extreme_comparisons)]
30723 #[allow(unused_comparisons)]
30724 if __tmp.remaining() < Self::ENCODED_LEN {
30725 panic!(
30726 "buffer is too small (need {} bytes, but got {})",
30727 Self::ENCODED_LEN,
30728 __tmp.remaining(),
30729 )
30730 }
30731 __tmp.put_u16_le(self.message_type);
30732 __tmp.put_u8(self.target_network);
30733 __tmp.put_u8(self.target_system);
30734 __tmp.put_u8(self.target_component);
30735 for val in &self.payload {
30736 __tmp.put_u8(*val);
30737 }
30738 if matches!(version, MavlinkVersion::V2) {
30739 let len = __tmp.len();
30740 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30741 } else {
30742 __tmp.len()
30743 }
30744 }
30745}
30746#[doc = "id: 74"]
30747#[doc = "Metrics typically displayed on a HUD for fixed wing aircraft."]
30748#[derive(Debug, Clone, PartialEq)]
30749#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30750#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30751pub struct VFR_HUD_DATA {
30752 #[doc = "Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed."]
30753 pub airspeed: f32,
30754 #[doc = "Current ground speed."]
30755 pub groundspeed: f32,
30756 #[doc = "Current altitude (MSL)."]
30757 pub alt: f32,
30758 #[doc = "Current climb rate."]
30759 pub climb: f32,
30760 #[doc = "Current heading in compass units (0-360, 0=north)."]
30761 pub heading: i16,
30762 #[doc = "Current throttle setting (0 to 100)."]
30763 pub throttle: u16,
30764}
30765impl VFR_HUD_DATA {
30766 pub const ENCODED_LEN: usize = 20usize;
30767 pub const DEFAULT: Self = Self {
30768 airspeed: 0.0_f32,
30769 groundspeed: 0.0_f32,
30770 alt: 0.0_f32,
30771 climb: 0.0_f32,
30772 heading: 0_i16,
30773 throttle: 0_u16,
30774 };
30775 #[cfg(feature = "arbitrary")]
30776 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30777 use arbitrary::{Arbitrary, Unstructured};
30778 let mut buf = [0u8; 1024];
30779 rng.fill_bytes(&mut buf);
30780 let mut unstructured = Unstructured::new(&buf);
30781 Self::arbitrary(&mut unstructured).unwrap_or_default()
30782 }
30783}
30784impl Default for VFR_HUD_DATA {
30785 fn default() -> Self {
30786 Self::DEFAULT.clone()
30787 }
30788}
30789impl MessageData for VFR_HUD_DATA {
30790 type Message = MavMessage;
30791 const ID: u32 = 74u32;
30792 const NAME: &'static str = "VFR_HUD";
30793 const EXTRA_CRC: u8 = 20u8;
30794 const ENCODED_LEN: usize = 20usize;
30795 fn deser(
30796 _version: MavlinkVersion,
30797 __input: &[u8],
30798 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30799 let avail_len = __input.len();
30800 let mut payload_buf = [0; Self::ENCODED_LEN];
30801 let mut buf = if avail_len < Self::ENCODED_LEN {
30802 payload_buf[0..avail_len].copy_from_slice(__input);
30803 Bytes::new(&payload_buf)
30804 } else {
30805 Bytes::new(__input)
30806 };
30807 let mut __struct = Self::default();
30808 __struct.airspeed = buf.get_f32_le();
30809 __struct.groundspeed = buf.get_f32_le();
30810 __struct.alt = buf.get_f32_le();
30811 __struct.climb = buf.get_f32_le();
30812 __struct.heading = buf.get_i16_le();
30813 __struct.throttle = buf.get_u16_le();
30814 Ok(__struct)
30815 }
30816 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30817 let mut __tmp = BytesMut::new(bytes);
30818 #[allow(clippy::absurd_extreme_comparisons)]
30819 #[allow(unused_comparisons)]
30820 if __tmp.remaining() < Self::ENCODED_LEN {
30821 panic!(
30822 "buffer is too small (need {} bytes, but got {})",
30823 Self::ENCODED_LEN,
30824 __tmp.remaining(),
30825 )
30826 }
30827 __tmp.put_f32_le(self.airspeed);
30828 __tmp.put_f32_le(self.groundspeed);
30829 __tmp.put_f32_le(self.alt);
30830 __tmp.put_f32_le(self.climb);
30831 __tmp.put_i16_le(self.heading);
30832 __tmp.put_u16_le(self.throttle);
30833 if matches!(version, MavlinkVersion::V2) {
30834 let len = __tmp.len();
30835 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30836 } else {
30837 __tmp.len()
30838 }
30839 }
30840}
30841#[doc = "id: 241"]
30842#[doc = "Vibration levels and accelerometer clipping."]
30843#[derive(Debug, Clone, PartialEq)]
30844#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30845#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30846pub struct VIBRATION_DATA {
30847 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
30848 pub time_usec: u64,
30849 #[doc = "Vibration levels on X-axis"]
30850 pub vibration_x: f32,
30851 #[doc = "Vibration levels on Y-axis"]
30852 pub vibration_y: f32,
30853 #[doc = "Vibration levels on Z-axis"]
30854 pub vibration_z: f32,
30855 #[doc = "first accelerometer clipping count"]
30856 pub clipping_0: u32,
30857 #[doc = "second accelerometer clipping count"]
30858 pub clipping_1: u32,
30859 #[doc = "third accelerometer clipping count"]
30860 pub clipping_2: u32,
30861}
30862impl VIBRATION_DATA {
30863 pub const ENCODED_LEN: usize = 32usize;
30864 pub const DEFAULT: Self = Self {
30865 time_usec: 0_u64,
30866 vibration_x: 0.0_f32,
30867 vibration_y: 0.0_f32,
30868 vibration_z: 0.0_f32,
30869 clipping_0: 0_u32,
30870 clipping_1: 0_u32,
30871 clipping_2: 0_u32,
30872 };
30873 #[cfg(feature = "arbitrary")]
30874 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30875 use arbitrary::{Arbitrary, Unstructured};
30876 let mut buf = [0u8; 1024];
30877 rng.fill_bytes(&mut buf);
30878 let mut unstructured = Unstructured::new(&buf);
30879 Self::arbitrary(&mut unstructured).unwrap_or_default()
30880 }
30881}
30882impl Default for VIBRATION_DATA {
30883 fn default() -> Self {
30884 Self::DEFAULT.clone()
30885 }
30886}
30887impl MessageData for VIBRATION_DATA {
30888 type Message = MavMessage;
30889 const ID: u32 = 241u32;
30890 const NAME: &'static str = "VIBRATION";
30891 const EXTRA_CRC: u8 = 90u8;
30892 const ENCODED_LEN: usize = 32usize;
30893 fn deser(
30894 _version: MavlinkVersion,
30895 __input: &[u8],
30896 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30897 let avail_len = __input.len();
30898 let mut payload_buf = [0; Self::ENCODED_LEN];
30899 let mut buf = if avail_len < Self::ENCODED_LEN {
30900 payload_buf[0..avail_len].copy_from_slice(__input);
30901 Bytes::new(&payload_buf)
30902 } else {
30903 Bytes::new(__input)
30904 };
30905 let mut __struct = Self::default();
30906 __struct.time_usec = buf.get_u64_le();
30907 __struct.vibration_x = buf.get_f32_le();
30908 __struct.vibration_y = buf.get_f32_le();
30909 __struct.vibration_z = buf.get_f32_le();
30910 __struct.clipping_0 = buf.get_u32_le();
30911 __struct.clipping_1 = buf.get_u32_le();
30912 __struct.clipping_2 = buf.get_u32_le();
30913 Ok(__struct)
30914 }
30915 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30916 let mut __tmp = BytesMut::new(bytes);
30917 #[allow(clippy::absurd_extreme_comparisons)]
30918 #[allow(unused_comparisons)]
30919 if __tmp.remaining() < Self::ENCODED_LEN {
30920 panic!(
30921 "buffer is too small (need {} bytes, but got {})",
30922 Self::ENCODED_LEN,
30923 __tmp.remaining(),
30924 )
30925 }
30926 __tmp.put_u64_le(self.time_usec);
30927 __tmp.put_f32_le(self.vibration_x);
30928 __tmp.put_f32_le(self.vibration_y);
30929 __tmp.put_f32_le(self.vibration_z);
30930 __tmp.put_u32_le(self.clipping_0);
30931 __tmp.put_u32_le(self.clipping_1);
30932 __tmp.put_u32_le(self.clipping_2);
30933 if matches!(version, MavlinkVersion::V2) {
30934 let len = __tmp.len();
30935 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30936 } else {
30937 __tmp.len()
30938 }
30939 }
30940}
30941#[doc = "id: 104"]
30942#[doc = "Global position estimate from a Vicon motion system source."]
30943#[derive(Debug, Clone, PartialEq)]
30944#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30945#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30946pub struct VICON_POSITION_ESTIMATE_DATA {
30947 #[doc = "Timestamp (UNIX time or time since system boot)"]
30948 pub usec: u64,
30949 #[doc = "Global X position"]
30950 pub x: f32,
30951 #[doc = "Global Y position"]
30952 pub y: f32,
30953 #[doc = "Global Z position"]
30954 pub z: f32,
30955 #[doc = "Roll angle"]
30956 pub roll: f32,
30957 #[doc = "Pitch angle"]
30958 pub pitch: f32,
30959 #[doc = "Yaw angle"]
30960 pub yaw: f32,
30961 #[doc = "Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
30962 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30963 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30964 pub covariance: [f32; 21],
30965}
30966impl VICON_POSITION_ESTIMATE_DATA {
30967 pub const ENCODED_LEN: usize = 116usize;
30968 pub const DEFAULT: Self = Self {
30969 usec: 0_u64,
30970 x: 0.0_f32,
30971 y: 0.0_f32,
30972 z: 0.0_f32,
30973 roll: 0.0_f32,
30974 pitch: 0.0_f32,
30975 yaw: 0.0_f32,
30976 covariance: [0.0_f32; 21usize],
30977 };
30978 #[cfg(feature = "arbitrary")]
30979 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30980 use arbitrary::{Arbitrary, Unstructured};
30981 let mut buf = [0u8; 1024];
30982 rng.fill_bytes(&mut buf);
30983 let mut unstructured = Unstructured::new(&buf);
30984 Self::arbitrary(&mut unstructured).unwrap_or_default()
30985 }
30986}
30987impl Default for VICON_POSITION_ESTIMATE_DATA {
30988 fn default() -> Self {
30989 Self::DEFAULT.clone()
30990 }
30991}
30992impl MessageData for VICON_POSITION_ESTIMATE_DATA {
30993 type Message = MavMessage;
30994 const ID: u32 = 104u32;
30995 const NAME: &'static str = "VICON_POSITION_ESTIMATE";
30996 const EXTRA_CRC: u8 = 56u8;
30997 const ENCODED_LEN: usize = 116usize;
30998 fn deser(
30999 _version: MavlinkVersion,
31000 __input: &[u8],
31001 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31002 let avail_len = __input.len();
31003 let mut payload_buf = [0; Self::ENCODED_LEN];
31004 let mut buf = if avail_len < Self::ENCODED_LEN {
31005 payload_buf[0..avail_len].copy_from_slice(__input);
31006 Bytes::new(&payload_buf)
31007 } else {
31008 Bytes::new(__input)
31009 };
31010 let mut __struct = Self::default();
31011 __struct.usec = buf.get_u64_le();
31012 __struct.x = buf.get_f32_le();
31013 __struct.y = buf.get_f32_le();
31014 __struct.z = buf.get_f32_le();
31015 __struct.roll = buf.get_f32_le();
31016 __struct.pitch = buf.get_f32_le();
31017 __struct.yaw = buf.get_f32_le();
31018 for v in &mut __struct.covariance {
31019 let val = buf.get_f32_le();
31020 *v = val;
31021 }
31022 Ok(__struct)
31023 }
31024 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31025 let mut __tmp = BytesMut::new(bytes);
31026 #[allow(clippy::absurd_extreme_comparisons)]
31027 #[allow(unused_comparisons)]
31028 if __tmp.remaining() < Self::ENCODED_LEN {
31029 panic!(
31030 "buffer is too small (need {} bytes, but got {})",
31031 Self::ENCODED_LEN,
31032 __tmp.remaining(),
31033 )
31034 }
31035 __tmp.put_u64_le(self.usec);
31036 __tmp.put_f32_le(self.x);
31037 __tmp.put_f32_le(self.y);
31038 __tmp.put_f32_le(self.z);
31039 __tmp.put_f32_le(self.roll);
31040 __tmp.put_f32_le(self.pitch);
31041 __tmp.put_f32_le(self.yaw);
31042 for val in &self.covariance {
31043 __tmp.put_f32_le(*val);
31044 }
31045 if matches!(version, MavlinkVersion::V2) {
31046 let len = __tmp.len();
31047 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31048 } else {
31049 __tmp.len()
31050 }
31051 }
31052}
31053#[doc = "id: 269"]
31054#[doc = "Information about video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE, where param2 indicates the video stream id: 0 for all streams, 1 for first, 2 for second, etc."]
31055#[derive(Debug, Clone, PartialEq)]
31056#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31057#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31058pub struct VIDEO_STREAM_INFORMATION_DATA {
31059 #[doc = "Frame rate."]
31060 pub framerate: f32,
31061 #[doc = "Bit rate."]
31062 pub bitrate: u32,
31063 #[doc = "Bitmap of stream status flags."]
31064 pub flags: VideoStreamStatusFlags,
31065 #[doc = "Horizontal resolution."]
31066 pub resolution_h: u16,
31067 #[doc = "Vertical resolution."]
31068 pub resolution_v: u16,
31069 #[doc = "Video image rotation clockwise."]
31070 pub rotation: u16,
31071 #[doc = "Horizontal Field of view."]
31072 pub hfov: u16,
31073 #[doc = "Video Stream ID (1 for first, 2 for second, etc.)"]
31074 pub stream_id: u8,
31075 #[doc = "Number of streams available."]
31076 pub count: u8,
31077 #[doc = "Type of stream."]
31078 pub mavtype: VideoStreamType,
31079 #[doc = "Stream name."]
31080 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31081 pub name: [u8; 32],
31082 #[doc = "Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to)."]
31083 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31084 pub uri: [u8; 160],
31085 #[doc = "Encoding of stream."]
31086 #[cfg_attr(feature = "serde", serde(default))]
31087 pub encoding: VideoStreamEncoding,
31088 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
31089 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
31090 pub camera_device_id: u8,
31091}
31092impl VIDEO_STREAM_INFORMATION_DATA {
31093 pub const ENCODED_LEN: usize = 215usize;
31094 pub const DEFAULT: Self = Self {
31095 framerate: 0.0_f32,
31096 bitrate: 0_u32,
31097 flags: VideoStreamStatusFlags::DEFAULT,
31098 resolution_h: 0_u16,
31099 resolution_v: 0_u16,
31100 rotation: 0_u16,
31101 hfov: 0_u16,
31102 stream_id: 0_u8,
31103 count: 0_u8,
31104 mavtype: VideoStreamType::DEFAULT,
31105 name: [0_u8; 32usize],
31106 uri: [0_u8; 160usize],
31107 encoding: VideoStreamEncoding::DEFAULT,
31108 camera_device_id: 0_u8,
31109 };
31110 #[cfg(feature = "arbitrary")]
31111 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31112 use arbitrary::{Arbitrary, Unstructured};
31113 let mut buf = [0u8; 1024];
31114 rng.fill_bytes(&mut buf);
31115 let mut unstructured = Unstructured::new(&buf);
31116 Self::arbitrary(&mut unstructured).unwrap_or_default()
31117 }
31118}
31119impl Default for VIDEO_STREAM_INFORMATION_DATA {
31120 fn default() -> Self {
31121 Self::DEFAULT.clone()
31122 }
31123}
31124impl MessageData for VIDEO_STREAM_INFORMATION_DATA {
31125 type Message = MavMessage;
31126 const ID: u32 = 269u32;
31127 const NAME: &'static str = "VIDEO_STREAM_INFORMATION";
31128 const EXTRA_CRC: u8 = 109u8;
31129 const ENCODED_LEN: usize = 215usize;
31130 fn deser(
31131 _version: MavlinkVersion,
31132 __input: &[u8],
31133 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31134 let avail_len = __input.len();
31135 let mut payload_buf = [0; Self::ENCODED_LEN];
31136 let mut buf = if avail_len < Self::ENCODED_LEN {
31137 payload_buf[0..avail_len].copy_from_slice(__input);
31138 Bytes::new(&payload_buf)
31139 } else {
31140 Bytes::new(__input)
31141 };
31142 let mut __struct = Self::default();
31143 __struct.framerate = buf.get_f32_le();
31144 __struct.bitrate = buf.get_u32_le();
31145 let tmp = buf.get_u16_le();
31146 __struct.flags = VideoStreamStatusFlags::from_bits(
31147 tmp & VideoStreamStatusFlags::all().bits(),
31148 )
31149 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
31150 flag_type: "VideoStreamStatusFlags",
31151 value: tmp as u32,
31152 })?;
31153 __struct.resolution_h = buf.get_u16_le();
31154 __struct.resolution_v = buf.get_u16_le();
31155 __struct.rotation = buf.get_u16_le();
31156 __struct.hfov = buf.get_u16_le();
31157 __struct.stream_id = buf.get_u8();
31158 __struct.count = buf.get_u8();
31159 let tmp = buf.get_u8();
31160 __struct.mavtype =
31161 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
31162 enum_type: "VideoStreamType",
31163 value: tmp as u32,
31164 })?;
31165 for v in &mut __struct.name {
31166 let val = buf.get_u8();
31167 *v = val;
31168 }
31169 for v in &mut __struct.uri {
31170 let val = buf.get_u8();
31171 *v = val;
31172 }
31173 let tmp = buf.get_u8();
31174 __struct.encoding =
31175 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
31176 enum_type: "VideoStreamEncoding",
31177 value: tmp as u32,
31178 })?;
31179 __struct.camera_device_id = buf.get_u8();
31180 Ok(__struct)
31181 }
31182 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31183 let mut __tmp = BytesMut::new(bytes);
31184 #[allow(clippy::absurd_extreme_comparisons)]
31185 #[allow(unused_comparisons)]
31186 if __tmp.remaining() < Self::ENCODED_LEN {
31187 panic!(
31188 "buffer is too small (need {} bytes, but got {})",
31189 Self::ENCODED_LEN,
31190 __tmp.remaining(),
31191 )
31192 }
31193 __tmp.put_f32_le(self.framerate);
31194 __tmp.put_u32_le(self.bitrate);
31195 __tmp.put_u16_le(self.flags.bits());
31196 __tmp.put_u16_le(self.resolution_h);
31197 __tmp.put_u16_le(self.resolution_v);
31198 __tmp.put_u16_le(self.rotation);
31199 __tmp.put_u16_le(self.hfov);
31200 __tmp.put_u8(self.stream_id);
31201 __tmp.put_u8(self.count);
31202 __tmp.put_u8(self.mavtype as u8);
31203 for val in &self.name {
31204 __tmp.put_u8(*val);
31205 }
31206 for val in &self.uri {
31207 __tmp.put_u8(*val);
31208 }
31209 __tmp.put_u8(self.encoding as u8);
31210 __tmp.put_u8(self.camera_device_id);
31211 if matches!(version, MavlinkVersion::V2) {
31212 let len = __tmp.len();
31213 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31214 } else {
31215 __tmp.len()
31216 }
31217 }
31218}
31219#[doc = "id: 270"]
31220#[doc = "Information about the status of a video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE."]
31221#[derive(Debug, Clone, PartialEq)]
31222#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31223#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31224pub struct VIDEO_STREAM_STATUS_DATA {
31225 #[doc = "Frame rate"]
31226 pub framerate: f32,
31227 #[doc = "Bit rate"]
31228 pub bitrate: u32,
31229 #[doc = "Bitmap of stream status flags"]
31230 pub flags: VideoStreamStatusFlags,
31231 #[doc = "Horizontal resolution"]
31232 pub resolution_h: u16,
31233 #[doc = "Vertical resolution"]
31234 pub resolution_v: u16,
31235 #[doc = "Video image rotation clockwise"]
31236 pub rotation: u16,
31237 #[doc = "Horizontal Field of view"]
31238 pub hfov: u16,
31239 #[doc = "Video Stream ID (1 for first, 2 for second, etc.)"]
31240 pub stream_id: u8,
31241 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
31242 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
31243 pub camera_device_id: u8,
31244}
31245impl VIDEO_STREAM_STATUS_DATA {
31246 pub const ENCODED_LEN: usize = 20usize;
31247 pub const DEFAULT: Self = Self {
31248 framerate: 0.0_f32,
31249 bitrate: 0_u32,
31250 flags: VideoStreamStatusFlags::DEFAULT,
31251 resolution_h: 0_u16,
31252 resolution_v: 0_u16,
31253 rotation: 0_u16,
31254 hfov: 0_u16,
31255 stream_id: 0_u8,
31256 camera_device_id: 0_u8,
31257 };
31258 #[cfg(feature = "arbitrary")]
31259 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31260 use arbitrary::{Arbitrary, Unstructured};
31261 let mut buf = [0u8; 1024];
31262 rng.fill_bytes(&mut buf);
31263 let mut unstructured = Unstructured::new(&buf);
31264 Self::arbitrary(&mut unstructured).unwrap_or_default()
31265 }
31266}
31267impl Default for VIDEO_STREAM_STATUS_DATA {
31268 fn default() -> Self {
31269 Self::DEFAULT.clone()
31270 }
31271}
31272impl MessageData for VIDEO_STREAM_STATUS_DATA {
31273 type Message = MavMessage;
31274 const ID: u32 = 270u32;
31275 const NAME: &'static str = "VIDEO_STREAM_STATUS";
31276 const EXTRA_CRC: u8 = 59u8;
31277 const ENCODED_LEN: usize = 20usize;
31278 fn deser(
31279 _version: MavlinkVersion,
31280 __input: &[u8],
31281 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31282 let avail_len = __input.len();
31283 let mut payload_buf = [0; Self::ENCODED_LEN];
31284 let mut buf = if avail_len < Self::ENCODED_LEN {
31285 payload_buf[0..avail_len].copy_from_slice(__input);
31286 Bytes::new(&payload_buf)
31287 } else {
31288 Bytes::new(__input)
31289 };
31290 let mut __struct = Self::default();
31291 __struct.framerate = buf.get_f32_le();
31292 __struct.bitrate = buf.get_u32_le();
31293 let tmp = buf.get_u16_le();
31294 __struct.flags = VideoStreamStatusFlags::from_bits(
31295 tmp & VideoStreamStatusFlags::all().bits(),
31296 )
31297 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
31298 flag_type: "VideoStreamStatusFlags",
31299 value: tmp as u32,
31300 })?;
31301 __struct.resolution_h = buf.get_u16_le();
31302 __struct.resolution_v = buf.get_u16_le();
31303 __struct.rotation = buf.get_u16_le();
31304 __struct.hfov = buf.get_u16_le();
31305 __struct.stream_id = buf.get_u8();
31306 __struct.camera_device_id = buf.get_u8();
31307 Ok(__struct)
31308 }
31309 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31310 let mut __tmp = BytesMut::new(bytes);
31311 #[allow(clippy::absurd_extreme_comparisons)]
31312 #[allow(unused_comparisons)]
31313 if __tmp.remaining() < Self::ENCODED_LEN {
31314 panic!(
31315 "buffer is too small (need {} bytes, but got {})",
31316 Self::ENCODED_LEN,
31317 __tmp.remaining(),
31318 )
31319 }
31320 __tmp.put_f32_le(self.framerate);
31321 __tmp.put_u32_le(self.bitrate);
31322 __tmp.put_u16_le(self.flags.bits());
31323 __tmp.put_u16_le(self.resolution_h);
31324 __tmp.put_u16_le(self.resolution_v);
31325 __tmp.put_u16_le(self.rotation);
31326 __tmp.put_u16_le(self.hfov);
31327 __tmp.put_u8(self.stream_id);
31328 __tmp.put_u8(self.camera_device_id);
31329 if matches!(version, MavlinkVersion::V2) {
31330 let len = __tmp.len();
31331 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31332 } else {
31333 __tmp.len()
31334 }
31335 }
31336}
31337#[doc = "id: 102"]
31338#[doc = "Local position/attitude estimate from a vision source."]
31339#[derive(Debug, Clone, PartialEq)]
31340#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31341#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31342pub struct VISION_POSITION_ESTIMATE_DATA {
31343 #[doc = "Timestamp (UNIX time or time since system boot)"]
31344 pub usec: u64,
31345 #[doc = "Local X position"]
31346 pub x: f32,
31347 #[doc = "Local Y position"]
31348 pub y: f32,
31349 #[doc = "Local Z position"]
31350 pub z: f32,
31351 #[doc = "Roll angle"]
31352 pub roll: f32,
31353 #[doc = "Pitch angle"]
31354 pub pitch: f32,
31355 #[doc = "Yaw angle"]
31356 pub yaw: f32,
31357 #[doc = "Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
31358 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
31359 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31360 pub covariance: [f32; 21],
31361 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
31362 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
31363 pub reset_counter: u8,
31364}
31365impl VISION_POSITION_ESTIMATE_DATA {
31366 pub const ENCODED_LEN: usize = 117usize;
31367 pub const DEFAULT: Self = Self {
31368 usec: 0_u64,
31369 x: 0.0_f32,
31370 y: 0.0_f32,
31371 z: 0.0_f32,
31372 roll: 0.0_f32,
31373 pitch: 0.0_f32,
31374 yaw: 0.0_f32,
31375 covariance: [0.0_f32; 21usize],
31376 reset_counter: 0_u8,
31377 };
31378 #[cfg(feature = "arbitrary")]
31379 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31380 use arbitrary::{Arbitrary, Unstructured};
31381 let mut buf = [0u8; 1024];
31382 rng.fill_bytes(&mut buf);
31383 let mut unstructured = Unstructured::new(&buf);
31384 Self::arbitrary(&mut unstructured).unwrap_or_default()
31385 }
31386}
31387impl Default for VISION_POSITION_ESTIMATE_DATA {
31388 fn default() -> Self {
31389 Self::DEFAULT.clone()
31390 }
31391}
31392impl MessageData for VISION_POSITION_ESTIMATE_DATA {
31393 type Message = MavMessage;
31394 const ID: u32 = 102u32;
31395 const NAME: &'static str = "VISION_POSITION_ESTIMATE";
31396 const EXTRA_CRC: u8 = 158u8;
31397 const ENCODED_LEN: usize = 117usize;
31398 fn deser(
31399 _version: MavlinkVersion,
31400 __input: &[u8],
31401 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31402 let avail_len = __input.len();
31403 let mut payload_buf = [0; Self::ENCODED_LEN];
31404 let mut buf = if avail_len < Self::ENCODED_LEN {
31405 payload_buf[0..avail_len].copy_from_slice(__input);
31406 Bytes::new(&payload_buf)
31407 } else {
31408 Bytes::new(__input)
31409 };
31410 let mut __struct = Self::default();
31411 __struct.usec = buf.get_u64_le();
31412 __struct.x = buf.get_f32_le();
31413 __struct.y = buf.get_f32_le();
31414 __struct.z = buf.get_f32_le();
31415 __struct.roll = buf.get_f32_le();
31416 __struct.pitch = buf.get_f32_le();
31417 __struct.yaw = buf.get_f32_le();
31418 for v in &mut __struct.covariance {
31419 let val = buf.get_f32_le();
31420 *v = val;
31421 }
31422 __struct.reset_counter = buf.get_u8();
31423 Ok(__struct)
31424 }
31425 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31426 let mut __tmp = BytesMut::new(bytes);
31427 #[allow(clippy::absurd_extreme_comparisons)]
31428 #[allow(unused_comparisons)]
31429 if __tmp.remaining() < Self::ENCODED_LEN {
31430 panic!(
31431 "buffer is too small (need {} bytes, but got {})",
31432 Self::ENCODED_LEN,
31433 __tmp.remaining(),
31434 )
31435 }
31436 __tmp.put_u64_le(self.usec);
31437 __tmp.put_f32_le(self.x);
31438 __tmp.put_f32_le(self.y);
31439 __tmp.put_f32_le(self.z);
31440 __tmp.put_f32_le(self.roll);
31441 __tmp.put_f32_le(self.pitch);
31442 __tmp.put_f32_le(self.yaw);
31443 for val in &self.covariance {
31444 __tmp.put_f32_le(*val);
31445 }
31446 __tmp.put_u8(self.reset_counter);
31447 if matches!(version, MavlinkVersion::V2) {
31448 let len = __tmp.len();
31449 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31450 } else {
31451 __tmp.len()
31452 }
31453 }
31454}
31455#[doc = "id: 103"]
31456#[doc = "Speed estimate from a vision source."]
31457#[derive(Debug, Clone, PartialEq)]
31458#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31459#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31460pub struct VISION_SPEED_ESTIMATE_DATA {
31461 #[doc = "Timestamp (UNIX time or time since system boot)"]
31462 pub usec: u64,
31463 #[doc = "Global X speed"]
31464 pub x: f32,
31465 #[doc = "Global Y speed"]
31466 pub y: f32,
31467 #[doc = "Global Z speed"]
31468 pub z: f32,
31469 #[doc = "Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array."]
31470 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
31471 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31472 pub covariance: [f32; 9],
31473 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
31474 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
31475 pub reset_counter: u8,
31476}
31477impl VISION_SPEED_ESTIMATE_DATA {
31478 pub const ENCODED_LEN: usize = 57usize;
31479 pub const DEFAULT: Self = Self {
31480 usec: 0_u64,
31481 x: 0.0_f32,
31482 y: 0.0_f32,
31483 z: 0.0_f32,
31484 covariance: [0.0_f32; 9usize],
31485 reset_counter: 0_u8,
31486 };
31487 #[cfg(feature = "arbitrary")]
31488 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31489 use arbitrary::{Arbitrary, Unstructured};
31490 let mut buf = [0u8; 1024];
31491 rng.fill_bytes(&mut buf);
31492 let mut unstructured = Unstructured::new(&buf);
31493 Self::arbitrary(&mut unstructured).unwrap_or_default()
31494 }
31495}
31496impl Default for VISION_SPEED_ESTIMATE_DATA {
31497 fn default() -> Self {
31498 Self::DEFAULT.clone()
31499 }
31500}
31501impl MessageData for VISION_SPEED_ESTIMATE_DATA {
31502 type Message = MavMessage;
31503 const ID: u32 = 103u32;
31504 const NAME: &'static str = "VISION_SPEED_ESTIMATE";
31505 const EXTRA_CRC: u8 = 208u8;
31506 const ENCODED_LEN: usize = 57usize;
31507 fn deser(
31508 _version: MavlinkVersion,
31509 __input: &[u8],
31510 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31511 let avail_len = __input.len();
31512 let mut payload_buf = [0; Self::ENCODED_LEN];
31513 let mut buf = if avail_len < Self::ENCODED_LEN {
31514 payload_buf[0..avail_len].copy_from_slice(__input);
31515 Bytes::new(&payload_buf)
31516 } else {
31517 Bytes::new(__input)
31518 };
31519 let mut __struct = Self::default();
31520 __struct.usec = buf.get_u64_le();
31521 __struct.x = buf.get_f32_le();
31522 __struct.y = buf.get_f32_le();
31523 __struct.z = buf.get_f32_le();
31524 for v in &mut __struct.covariance {
31525 let val = buf.get_f32_le();
31526 *v = val;
31527 }
31528 __struct.reset_counter = buf.get_u8();
31529 Ok(__struct)
31530 }
31531 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31532 let mut __tmp = BytesMut::new(bytes);
31533 #[allow(clippy::absurd_extreme_comparisons)]
31534 #[allow(unused_comparisons)]
31535 if __tmp.remaining() < Self::ENCODED_LEN {
31536 panic!(
31537 "buffer is too small (need {} bytes, but got {})",
31538 Self::ENCODED_LEN,
31539 __tmp.remaining(),
31540 )
31541 }
31542 __tmp.put_u64_le(self.usec);
31543 __tmp.put_f32_le(self.x);
31544 __tmp.put_f32_le(self.y);
31545 __tmp.put_f32_le(self.z);
31546 for val in &self.covariance {
31547 __tmp.put_f32_le(*val);
31548 }
31549 __tmp.put_u8(self.reset_counter);
31550 if matches!(version, MavlinkVersion::V2) {
31551 let len = __tmp.len();
31552 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31553 } else {
31554 __tmp.len()
31555 }
31556 }
31557}
31558#[doc = "id: 9000"]
31559#[doc = "Cumulative distance traveled for each reported wheel."]
31560#[derive(Debug, Clone, PartialEq)]
31561#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31562#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31563pub struct WHEEL_DISTANCE_DATA {
31564 #[doc = "Timestamp (synced to UNIX time or since system boot)."]
31565 pub time_usec: u64,
31566 #[doc = "Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints."]
31567 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31568 pub distance: [f64; 16],
31569 #[doc = "Number of wheels reported."]
31570 pub count: u8,
31571}
31572impl WHEEL_DISTANCE_DATA {
31573 pub const ENCODED_LEN: usize = 137usize;
31574 pub const DEFAULT: Self = Self {
31575 time_usec: 0_u64,
31576 distance: [0.0_f64; 16usize],
31577 count: 0_u8,
31578 };
31579 #[cfg(feature = "arbitrary")]
31580 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31581 use arbitrary::{Arbitrary, Unstructured};
31582 let mut buf = [0u8; 1024];
31583 rng.fill_bytes(&mut buf);
31584 let mut unstructured = Unstructured::new(&buf);
31585 Self::arbitrary(&mut unstructured).unwrap_or_default()
31586 }
31587}
31588impl Default for WHEEL_DISTANCE_DATA {
31589 fn default() -> Self {
31590 Self::DEFAULT.clone()
31591 }
31592}
31593impl MessageData for WHEEL_DISTANCE_DATA {
31594 type Message = MavMessage;
31595 const ID: u32 = 9000u32;
31596 const NAME: &'static str = "WHEEL_DISTANCE";
31597 const EXTRA_CRC: u8 = 113u8;
31598 const ENCODED_LEN: usize = 137usize;
31599 fn deser(
31600 _version: MavlinkVersion,
31601 __input: &[u8],
31602 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31603 let avail_len = __input.len();
31604 let mut payload_buf = [0; Self::ENCODED_LEN];
31605 let mut buf = if avail_len < Self::ENCODED_LEN {
31606 payload_buf[0..avail_len].copy_from_slice(__input);
31607 Bytes::new(&payload_buf)
31608 } else {
31609 Bytes::new(__input)
31610 };
31611 let mut __struct = Self::default();
31612 __struct.time_usec = buf.get_u64_le();
31613 for v in &mut __struct.distance {
31614 let val = buf.get_f64_le();
31615 *v = val;
31616 }
31617 __struct.count = buf.get_u8();
31618 Ok(__struct)
31619 }
31620 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31621 let mut __tmp = BytesMut::new(bytes);
31622 #[allow(clippy::absurd_extreme_comparisons)]
31623 #[allow(unused_comparisons)]
31624 if __tmp.remaining() < Self::ENCODED_LEN {
31625 panic!(
31626 "buffer is too small (need {} bytes, but got {})",
31627 Self::ENCODED_LEN,
31628 __tmp.remaining(),
31629 )
31630 }
31631 __tmp.put_u64_le(self.time_usec);
31632 for val in &self.distance {
31633 __tmp.put_f64_le(*val);
31634 }
31635 __tmp.put_u8(self.count);
31636 if matches!(version, MavlinkVersion::V2) {
31637 let len = __tmp.len();
31638 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31639 } else {
31640 __tmp.len()
31641 }
31642 }
31643}
31644#[doc = "id: 299"]
31645#[doc = "Configure WiFi AP SSID, password, and mode. This message is re-emitted as an acknowledgement by the AP. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE."]
31646#[derive(Debug, Clone, PartialEq)]
31647#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31648#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31649pub struct WIFI_CONFIG_AP_DATA {
31650 #[doc = "Name of Wi-Fi network (SSID). Blank to leave it unchanged when setting. Current SSID when sent back as a response."]
31651 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31652 pub ssid: [u8; 32],
31653 #[doc = "Password. Blank for an open AP. MD5 hash when message is sent back as a response."]
31654 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31655 pub password: [u8; 64],
31656 #[doc = "WiFi Mode."]
31657 #[cfg_attr(feature = "serde", serde(default))]
31658 pub mode: WifiConfigApMode,
31659 #[doc = "Message acceptance response (sent back to GS)."]
31660 #[cfg_attr(feature = "serde", serde(default))]
31661 pub response: WifiConfigApResponse,
31662}
31663impl WIFI_CONFIG_AP_DATA {
31664 pub const ENCODED_LEN: usize = 98usize;
31665 pub const DEFAULT: Self = Self {
31666 ssid: [0_u8; 32usize],
31667 password: [0_u8; 64usize],
31668 mode: WifiConfigApMode::DEFAULT,
31669 response: WifiConfigApResponse::DEFAULT,
31670 };
31671 #[cfg(feature = "arbitrary")]
31672 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31673 use arbitrary::{Arbitrary, Unstructured};
31674 let mut buf = [0u8; 1024];
31675 rng.fill_bytes(&mut buf);
31676 let mut unstructured = Unstructured::new(&buf);
31677 Self::arbitrary(&mut unstructured).unwrap_or_default()
31678 }
31679}
31680impl Default for WIFI_CONFIG_AP_DATA {
31681 fn default() -> Self {
31682 Self::DEFAULT.clone()
31683 }
31684}
31685impl MessageData for WIFI_CONFIG_AP_DATA {
31686 type Message = MavMessage;
31687 const ID: u32 = 299u32;
31688 const NAME: &'static str = "WIFI_CONFIG_AP";
31689 const EXTRA_CRC: u8 = 19u8;
31690 const ENCODED_LEN: usize = 98usize;
31691 fn deser(
31692 _version: MavlinkVersion,
31693 __input: &[u8],
31694 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31695 let avail_len = __input.len();
31696 let mut payload_buf = [0; Self::ENCODED_LEN];
31697 let mut buf = if avail_len < Self::ENCODED_LEN {
31698 payload_buf[0..avail_len].copy_from_slice(__input);
31699 Bytes::new(&payload_buf)
31700 } else {
31701 Bytes::new(__input)
31702 };
31703 let mut __struct = Self::default();
31704 for v in &mut __struct.ssid {
31705 let val = buf.get_u8();
31706 *v = val;
31707 }
31708 for v in &mut __struct.password {
31709 let val = buf.get_u8();
31710 *v = val;
31711 }
31712 let tmp = buf.get_i8();
31713 __struct.mode =
31714 FromPrimitive::from_i8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
31715 enum_type: "WifiConfigApMode",
31716 value: tmp as u32,
31717 })?;
31718 let tmp = buf.get_i8();
31719 __struct.response =
31720 FromPrimitive::from_i8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
31721 enum_type: "WifiConfigApResponse",
31722 value: tmp as u32,
31723 })?;
31724 Ok(__struct)
31725 }
31726 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31727 let mut __tmp = BytesMut::new(bytes);
31728 #[allow(clippy::absurd_extreme_comparisons)]
31729 #[allow(unused_comparisons)]
31730 if __tmp.remaining() < Self::ENCODED_LEN {
31731 panic!(
31732 "buffer is too small (need {} bytes, but got {})",
31733 Self::ENCODED_LEN,
31734 __tmp.remaining(),
31735 )
31736 }
31737 for val in &self.ssid {
31738 __tmp.put_u8(*val);
31739 }
31740 for val in &self.password {
31741 __tmp.put_u8(*val);
31742 }
31743 __tmp.put_i8(self.mode as i8);
31744 __tmp.put_i8(self.response as i8);
31745 if matches!(version, MavlinkVersion::V2) {
31746 let len = __tmp.len();
31747 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31748 } else {
31749 __tmp.len()
31750 }
31751 }
31752}
31753#[doc = "id: 9005"]
31754#[doc = "Winch status."]
31755#[derive(Debug, Clone, PartialEq)]
31756#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31757#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31758pub struct WINCH_STATUS_DATA {
31759 #[doc = "Timestamp (synced to UNIX time or since system boot)."]
31760 pub time_usec: u64,
31761 #[doc = "Length of line released. NaN if unknown"]
31762 pub line_length: f32,
31763 #[doc = "Speed line is being released or retracted. Positive values if being released, negative values if being retracted, NaN if unknown"]
31764 pub speed: f32,
31765 #[doc = "Tension on the line. NaN if unknown"]
31766 pub tension: f32,
31767 #[doc = "Voltage of the battery supplying the winch. NaN if unknown"]
31768 pub voltage: f32,
31769 #[doc = "Current draw from the winch. NaN if unknown"]
31770 pub current: f32,
31771 #[doc = "Status flags"]
31772 pub status: MavWinchStatusFlag,
31773 #[doc = "Temperature of the motor. INT16_MAX if unknown"]
31774 pub temperature: i16,
31775}
31776impl WINCH_STATUS_DATA {
31777 pub const ENCODED_LEN: usize = 34usize;
31778 pub const DEFAULT: Self = Self {
31779 time_usec: 0_u64,
31780 line_length: 0.0_f32,
31781 speed: 0.0_f32,
31782 tension: 0.0_f32,
31783 voltage: 0.0_f32,
31784 current: 0.0_f32,
31785 status: MavWinchStatusFlag::DEFAULT,
31786 temperature: 0_i16,
31787 };
31788 #[cfg(feature = "arbitrary")]
31789 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31790 use arbitrary::{Arbitrary, Unstructured};
31791 let mut buf = [0u8; 1024];
31792 rng.fill_bytes(&mut buf);
31793 let mut unstructured = Unstructured::new(&buf);
31794 Self::arbitrary(&mut unstructured).unwrap_or_default()
31795 }
31796}
31797impl Default for WINCH_STATUS_DATA {
31798 fn default() -> Self {
31799 Self::DEFAULT.clone()
31800 }
31801}
31802impl MessageData for WINCH_STATUS_DATA {
31803 type Message = MavMessage;
31804 const ID: u32 = 9005u32;
31805 const NAME: &'static str = "WINCH_STATUS";
31806 const EXTRA_CRC: u8 = 117u8;
31807 const ENCODED_LEN: usize = 34usize;
31808 fn deser(
31809 _version: MavlinkVersion,
31810 __input: &[u8],
31811 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31812 let avail_len = __input.len();
31813 let mut payload_buf = [0; Self::ENCODED_LEN];
31814 let mut buf = if avail_len < Self::ENCODED_LEN {
31815 payload_buf[0..avail_len].copy_from_slice(__input);
31816 Bytes::new(&payload_buf)
31817 } else {
31818 Bytes::new(__input)
31819 };
31820 let mut __struct = Self::default();
31821 __struct.time_usec = buf.get_u64_le();
31822 __struct.line_length = buf.get_f32_le();
31823 __struct.speed = buf.get_f32_le();
31824 __struct.tension = buf.get_f32_le();
31825 __struct.voltage = buf.get_f32_le();
31826 __struct.current = buf.get_f32_le();
31827 let tmp = buf.get_u32_le();
31828 __struct.status = MavWinchStatusFlag::from_bits(tmp & MavWinchStatusFlag::all().bits())
31829 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
31830 flag_type: "MavWinchStatusFlag",
31831 value: tmp as u32,
31832 })?;
31833 __struct.temperature = buf.get_i16_le();
31834 Ok(__struct)
31835 }
31836 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31837 let mut __tmp = BytesMut::new(bytes);
31838 #[allow(clippy::absurd_extreme_comparisons)]
31839 #[allow(unused_comparisons)]
31840 if __tmp.remaining() < Self::ENCODED_LEN {
31841 panic!(
31842 "buffer is too small (need {} bytes, but got {})",
31843 Self::ENCODED_LEN,
31844 __tmp.remaining(),
31845 )
31846 }
31847 __tmp.put_u64_le(self.time_usec);
31848 __tmp.put_f32_le(self.line_length);
31849 __tmp.put_f32_le(self.speed);
31850 __tmp.put_f32_le(self.tension);
31851 __tmp.put_f32_le(self.voltage);
31852 __tmp.put_f32_le(self.current);
31853 __tmp.put_u32_le(self.status.bits());
31854 __tmp.put_i16_le(self.temperature);
31855 if matches!(version, MavlinkVersion::V2) {
31856 let len = __tmp.len();
31857 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31858 } else {
31859 __tmp.len()
31860 }
31861 }
31862}
31863#[doc = "id: 231"]
31864#[doc = "Wind estimate from vehicle. Note that despite the name, this message does not actually contain any covariances but instead variability and accuracy fields in terms of standard deviation (1-STD)."]
31865#[derive(Debug, Clone, PartialEq)]
31866#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31867#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31868pub struct WIND_COV_DATA {
31869 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
31870 pub time_usec: u64,
31871 #[doc = "Wind in North (NED) direction (NAN if unknown)"]
31872 pub wind_x: f32,
31873 #[doc = "Wind in East (NED) direction (NAN if unknown)"]
31874 pub wind_y: f32,
31875 #[doc = "Wind in down (NED) direction (NAN if unknown)"]
31876 pub wind_z: f32,
31877 #[doc = "Variability of wind in XY, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown)"]
31878 pub var_horiz: f32,
31879 #[doc = "Variability of wind in Z, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown)"]
31880 pub var_vert: f32,
31881 #[doc = "Altitude (MSL) that this measurement was taken at (NAN if unknown)"]
31882 pub wind_alt: f32,
31883 #[doc = "Horizontal speed 1-STD accuracy (0 if unknown)"]
31884 pub horiz_accuracy: f32,
31885 #[doc = "Vertical speed 1-STD accuracy (0 if unknown)"]
31886 pub vert_accuracy: f32,
31887}
31888impl WIND_COV_DATA {
31889 pub const ENCODED_LEN: usize = 40usize;
31890 pub const DEFAULT: Self = Self {
31891 time_usec: 0_u64,
31892 wind_x: 0.0_f32,
31893 wind_y: 0.0_f32,
31894 wind_z: 0.0_f32,
31895 var_horiz: 0.0_f32,
31896 var_vert: 0.0_f32,
31897 wind_alt: 0.0_f32,
31898 horiz_accuracy: 0.0_f32,
31899 vert_accuracy: 0.0_f32,
31900 };
31901 #[cfg(feature = "arbitrary")]
31902 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31903 use arbitrary::{Arbitrary, Unstructured};
31904 let mut buf = [0u8; 1024];
31905 rng.fill_bytes(&mut buf);
31906 let mut unstructured = Unstructured::new(&buf);
31907 Self::arbitrary(&mut unstructured).unwrap_or_default()
31908 }
31909}
31910impl Default for WIND_COV_DATA {
31911 fn default() -> Self {
31912 Self::DEFAULT.clone()
31913 }
31914}
31915impl MessageData for WIND_COV_DATA {
31916 type Message = MavMessage;
31917 const ID: u32 = 231u32;
31918 const NAME: &'static str = "WIND_COV";
31919 const EXTRA_CRC: u8 = 105u8;
31920 const ENCODED_LEN: usize = 40usize;
31921 fn deser(
31922 _version: MavlinkVersion,
31923 __input: &[u8],
31924 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31925 let avail_len = __input.len();
31926 let mut payload_buf = [0; Self::ENCODED_LEN];
31927 let mut buf = if avail_len < Self::ENCODED_LEN {
31928 payload_buf[0..avail_len].copy_from_slice(__input);
31929 Bytes::new(&payload_buf)
31930 } else {
31931 Bytes::new(__input)
31932 };
31933 let mut __struct = Self::default();
31934 __struct.time_usec = buf.get_u64_le();
31935 __struct.wind_x = buf.get_f32_le();
31936 __struct.wind_y = buf.get_f32_le();
31937 __struct.wind_z = buf.get_f32_le();
31938 __struct.var_horiz = buf.get_f32_le();
31939 __struct.var_vert = buf.get_f32_le();
31940 __struct.wind_alt = buf.get_f32_le();
31941 __struct.horiz_accuracy = buf.get_f32_le();
31942 __struct.vert_accuracy = buf.get_f32_le();
31943 Ok(__struct)
31944 }
31945 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31946 let mut __tmp = BytesMut::new(bytes);
31947 #[allow(clippy::absurd_extreme_comparisons)]
31948 #[allow(unused_comparisons)]
31949 if __tmp.remaining() < Self::ENCODED_LEN {
31950 panic!(
31951 "buffer is too small (need {} bytes, but got {})",
31952 Self::ENCODED_LEN,
31953 __tmp.remaining(),
31954 )
31955 }
31956 __tmp.put_u64_le(self.time_usec);
31957 __tmp.put_f32_le(self.wind_x);
31958 __tmp.put_f32_le(self.wind_y);
31959 __tmp.put_f32_le(self.wind_z);
31960 __tmp.put_f32_le(self.var_horiz);
31961 __tmp.put_f32_le(self.var_vert);
31962 __tmp.put_f32_le(self.wind_alt);
31963 __tmp.put_f32_le(self.horiz_accuracy);
31964 __tmp.put_f32_le(self.vert_accuracy);
31965 if matches!(version, MavlinkVersion::V2) {
31966 let len = __tmp.len();
31967 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31968 } else {
31969 __tmp.len()
31970 }
31971 }
31972}
31973#[derive(Clone, PartialEq, Debug)]
31974#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31975#[cfg_attr(feature = "serde", serde(tag = "type"))]
31976#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31977#[repr(u32)]
31978pub enum MavMessage {
31979 ACTUATOR_CONTROL_TARGET(ACTUATOR_CONTROL_TARGET_DATA),
31980 ACTUATOR_OUTPUT_STATUS(ACTUATOR_OUTPUT_STATUS_DATA),
31981 ADSB_VEHICLE(ADSB_VEHICLE_DATA),
31982 AIS_VESSEL(AIS_VESSEL_DATA),
31983 ALTITUDE(ALTITUDE_DATA),
31984 ATTITUDE(ATTITUDE_DATA),
31985 ATTITUDE_QUATERNION(ATTITUDE_QUATERNION_DATA),
31986 ATTITUDE_QUATERNION_COV(ATTITUDE_QUATERNION_COV_DATA),
31987 ATTITUDE_TARGET(ATTITUDE_TARGET_DATA),
31988 ATT_POS_MOCAP(ATT_POS_MOCAP_DATA),
31989 AUTH_KEY(AUTH_KEY_DATA),
31990 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA),
31991 AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA),
31992 AVAILABLE_MODES(AVAILABLE_MODES_DATA),
31993 AVAILABLE_MODES_MONITOR(AVAILABLE_MODES_MONITOR_DATA),
31994 BATTERY_INFO(BATTERY_INFO_DATA),
31995 BATTERY_STATUS(BATTERY_STATUS_DATA),
31996 BUTTON_CHANGE(BUTTON_CHANGE_DATA),
31997 CAMERA_CAPTURE_STATUS(CAMERA_CAPTURE_STATUS_DATA),
31998 CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA),
31999 CAMERA_IMAGE_CAPTURED(CAMERA_IMAGE_CAPTURED_DATA),
32000 CAMERA_INFORMATION(CAMERA_INFORMATION_DATA),
32001 CAMERA_SETTINGS(CAMERA_SETTINGS_DATA),
32002 CAMERA_THERMAL_RANGE(CAMERA_THERMAL_RANGE_DATA),
32003 CAMERA_TRACKING_GEO_STATUS(CAMERA_TRACKING_GEO_STATUS_DATA),
32004 CAMERA_TRACKING_IMAGE_STATUS(CAMERA_TRACKING_IMAGE_STATUS_DATA),
32005 CAMERA_TRIGGER(CAMERA_TRIGGER_DATA),
32006 CANFD_FRAME(CANFD_FRAME_DATA),
32007 CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA),
32008 CAN_FRAME(CAN_FRAME_DATA),
32009 CELLULAR_CONFIG(CELLULAR_CONFIG_DATA),
32010 CELLULAR_STATUS(CELLULAR_STATUS_DATA),
32011 CHANGE_OPERATOR_CONTROL(CHANGE_OPERATOR_CONTROL_DATA),
32012 CHANGE_OPERATOR_CONTROL_ACK(CHANGE_OPERATOR_CONTROL_ACK_DATA),
32013 COLLISION(COLLISION_DATA),
32014 COMMAND_ACK(COMMAND_ACK_DATA),
32015 COMMAND_CANCEL(COMMAND_CANCEL_DATA),
32016 COMMAND_INT(COMMAND_INT_DATA),
32017 COMMAND_LONG(COMMAND_LONG_DATA),
32018 COMPONENT_INFORMATION(COMPONENT_INFORMATION_DATA),
32019 COMPONENT_INFORMATION_BASIC(COMPONENT_INFORMATION_BASIC_DATA),
32020 COMPONENT_METADATA(COMPONENT_METADATA_DATA),
32021 CONTROL_SYSTEM_STATE(CONTROL_SYSTEM_STATE_DATA),
32022 CURRENT_EVENT_SEQUENCE(CURRENT_EVENT_SEQUENCE_DATA),
32023 CURRENT_MODE(CURRENT_MODE_DATA),
32024 DATA_STREAM(DATA_STREAM_DATA),
32025 DATA_TRANSMISSION_HANDSHAKE(DATA_TRANSMISSION_HANDSHAKE_DATA),
32026 DEBUG(DEBUG_DATA),
32027 DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA),
32028 DEBUG_VECT(DEBUG_VECT_DATA),
32029 DISTANCE_SENSOR(DISTANCE_SENSOR_DATA),
32030 EFI_STATUS(EFI_STATUS_DATA),
32031 ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA),
32032 ESC_INFO(ESC_INFO_DATA),
32033 ESC_STATUS(ESC_STATUS_DATA),
32034 ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA),
32035 EVENT(EVENT_DATA),
32036 EXTENDED_SYS_STATE(EXTENDED_SYS_STATE_DATA),
32037 FENCE_STATUS(FENCE_STATUS_DATA),
32038 FILE_TRANSFER_PROTOCOL(FILE_TRANSFER_PROTOCOL_DATA),
32039 FLIGHT_INFORMATION(FLIGHT_INFORMATION_DATA),
32040 FOLLOW_TARGET(FOLLOW_TARGET_DATA),
32041 FUEL_STATUS(FUEL_STATUS_DATA),
32042 GENERATOR_STATUS(GENERATOR_STATUS_DATA),
32043 GIMBAL_DEVICE_ATTITUDE_STATUS(GIMBAL_DEVICE_ATTITUDE_STATUS_DATA),
32044 GIMBAL_DEVICE_INFORMATION(GIMBAL_DEVICE_INFORMATION_DATA),
32045 GIMBAL_DEVICE_SET_ATTITUDE(GIMBAL_DEVICE_SET_ATTITUDE_DATA),
32046 GIMBAL_MANAGER_INFORMATION(GIMBAL_MANAGER_INFORMATION_DATA),
32047 GIMBAL_MANAGER_SET_ATTITUDE(GIMBAL_MANAGER_SET_ATTITUDE_DATA),
32048 GIMBAL_MANAGER_SET_MANUAL_CONTROL(GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA),
32049 GIMBAL_MANAGER_SET_PITCHYAW(GIMBAL_MANAGER_SET_PITCHYAW_DATA),
32050 GIMBAL_MANAGER_STATUS(GIMBAL_MANAGER_STATUS_DATA),
32051 GLOBAL_POSITION_INT(GLOBAL_POSITION_INT_DATA),
32052 GLOBAL_POSITION_INT_COV(GLOBAL_POSITION_INT_COV_DATA),
32053 GLOBAL_VISION_POSITION_ESTIMATE(GLOBAL_VISION_POSITION_ESTIMATE_DATA),
32054 GPS2_RAW(GPS2_RAW_DATA),
32055 GPS2_RTK(GPS2_RTK_DATA),
32056 GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA),
32057 GPS_INJECT_DATA(GPS_INJECT_DATA_DATA),
32058 GPS_INPUT(GPS_INPUT_DATA),
32059 GPS_RAW_INT(GPS_RAW_INT_DATA),
32060 GPS_RTCM_DATA(GPS_RTCM_DATA_DATA),
32061 GPS_RTK(GPS_RTK_DATA),
32062 GPS_STATUS(GPS_STATUS_DATA),
32063 HEARTBEAT(HEARTBEAT_DATA),
32064 HIGHRES_IMU(HIGHRES_IMU_DATA),
32065 HIGH_LATENCY(HIGH_LATENCY_DATA),
32066 HIGH_LATENCY2(HIGH_LATENCY2_DATA),
32067 HIL_ACTUATOR_CONTROLS(HIL_ACTUATOR_CONTROLS_DATA),
32068 HIL_CONTROLS(HIL_CONTROLS_DATA),
32069 HIL_GPS(HIL_GPS_DATA),
32070 HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA),
32071 HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA),
32072 HIL_SENSOR(HIL_SENSOR_DATA),
32073 HIL_STATE(HIL_STATE_DATA),
32074 HIL_STATE_QUATERNION(HIL_STATE_QUATERNION_DATA),
32075 HOME_POSITION(HOME_POSITION_DATA),
32076 HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA),
32077 ILLUMINATOR_STATUS(ILLUMINATOR_STATUS_DATA),
32078 ISBD_LINK_STATUS(ISBD_LINK_STATUS_DATA),
32079 LANDING_TARGET(LANDING_TARGET_DATA),
32080 LINK_NODE_STATUS(LINK_NODE_STATUS_DATA),
32081 LOCAL_POSITION_NED(LOCAL_POSITION_NED_DATA),
32082 LOCAL_POSITION_NED_COV(LOCAL_POSITION_NED_COV_DATA),
32083 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA),
32084 LOGGING_ACK(LOGGING_ACK_DATA),
32085 LOGGING_DATA(LOGGING_DATA_DATA),
32086 LOGGING_DATA_ACKED(LOGGING_DATA_ACKED_DATA),
32087 LOG_DATA(LOG_DATA_DATA),
32088 LOG_ENTRY(LOG_ENTRY_DATA),
32089 LOG_ERASE(LOG_ERASE_DATA),
32090 LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA),
32091 LOG_REQUEST_END(LOG_REQUEST_END_DATA),
32092 LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA),
32093 MAG_CAL_REPORT(MAG_CAL_REPORT_DATA),
32094 MANUAL_CONTROL(MANUAL_CONTROL_DATA),
32095 MANUAL_SETPOINT(MANUAL_SETPOINT_DATA),
32096 MEMORY_VECT(MEMORY_VECT_DATA),
32097 MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA),
32098 MISSION_ACK(MISSION_ACK_DATA),
32099 MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA),
32100 MISSION_COUNT(MISSION_COUNT_DATA),
32101 MISSION_CURRENT(MISSION_CURRENT_DATA),
32102 MISSION_ITEM(MISSION_ITEM_DATA),
32103 MISSION_ITEM_INT(MISSION_ITEM_INT_DATA),
32104 MISSION_ITEM_REACHED(MISSION_ITEM_REACHED_DATA),
32105 MISSION_REQUEST(MISSION_REQUEST_DATA),
32106 MISSION_REQUEST_INT(MISSION_REQUEST_INT_DATA),
32107 MISSION_REQUEST_LIST(MISSION_REQUEST_LIST_DATA),
32108 MISSION_REQUEST_PARTIAL_LIST(MISSION_REQUEST_PARTIAL_LIST_DATA),
32109 MISSION_SET_CURRENT(MISSION_SET_CURRENT_DATA),
32110 MISSION_WRITE_PARTIAL_LIST(MISSION_WRITE_PARTIAL_LIST_DATA),
32111 MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA),
32112 NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA),
32113 NAMED_VALUE_INT(NAMED_VALUE_INT_DATA),
32114 NAV_CONTROLLER_OUTPUT(NAV_CONTROLLER_OUTPUT_DATA),
32115 OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA),
32116 ODOMETRY(ODOMETRY_DATA),
32117 ONBOARD_COMPUTER_STATUS(ONBOARD_COMPUTER_STATUS_DATA),
32118 OPEN_DRONE_ID_ARM_STATUS(OPEN_DRONE_ID_ARM_STATUS_DATA),
32119 OPEN_DRONE_ID_AUTHENTICATION(OPEN_DRONE_ID_AUTHENTICATION_DATA),
32120 OPEN_DRONE_ID_BASIC_ID(OPEN_DRONE_ID_BASIC_ID_DATA),
32121 OPEN_DRONE_ID_LOCATION(OPEN_DRONE_ID_LOCATION_DATA),
32122 OPEN_DRONE_ID_MESSAGE_PACK(OPEN_DRONE_ID_MESSAGE_PACK_DATA),
32123 OPEN_DRONE_ID_OPERATOR_ID(OPEN_DRONE_ID_OPERATOR_ID_DATA),
32124 OPEN_DRONE_ID_SELF_ID(OPEN_DRONE_ID_SELF_ID_DATA),
32125 OPEN_DRONE_ID_SYSTEM(OPEN_DRONE_ID_SYSTEM_DATA),
32126 OPEN_DRONE_ID_SYSTEM_UPDATE(OPEN_DRONE_ID_SYSTEM_UPDATE_DATA),
32127 OPTICAL_FLOW(OPTICAL_FLOW_DATA),
32128 OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA),
32129 ORBIT_EXECUTION_STATUS(ORBIT_EXECUTION_STATUS_DATA),
32130 PARAM_EXT_ACK(PARAM_EXT_ACK_DATA),
32131 PARAM_EXT_REQUEST_LIST(PARAM_EXT_REQUEST_LIST_DATA),
32132 PARAM_EXT_REQUEST_READ(PARAM_EXT_REQUEST_READ_DATA),
32133 PARAM_EXT_SET(PARAM_EXT_SET_DATA),
32134 PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA),
32135 PARAM_MAP_RC(PARAM_MAP_RC_DATA),
32136 PARAM_REQUEST_LIST(PARAM_REQUEST_LIST_DATA),
32137 PARAM_REQUEST_READ(PARAM_REQUEST_READ_DATA),
32138 PARAM_SET(PARAM_SET_DATA),
32139 PARAM_VALUE(PARAM_VALUE_DATA),
32140 PING(PING_DATA),
32141 PLAY_TUNE(PLAY_TUNE_DATA),
32142 PLAY_TUNE_V2(PLAY_TUNE_V2_DATA),
32143 POSITION_TARGET_GLOBAL_INT(POSITION_TARGET_GLOBAL_INT_DATA),
32144 POSITION_TARGET_LOCAL_NED(POSITION_TARGET_LOCAL_NED_DATA),
32145 POWER_STATUS(POWER_STATUS_DATA),
32146 PROTOCOL_VERSION(PROTOCOL_VERSION_DATA),
32147 RADIO_STATUS(RADIO_STATUS_DATA),
32148 RAW_IMU(RAW_IMU_DATA),
32149 RAW_PRESSURE(RAW_PRESSURE_DATA),
32150 RAW_RPM(RAW_RPM_DATA),
32151 RC_CHANNELS(RC_CHANNELS_DATA),
32152 RC_CHANNELS_OVERRIDE(RC_CHANNELS_OVERRIDE_DATA),
32153 RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA),
32154 RC_CHANNELS_SCALED(RC_CHANNELS_SCALED_DATA),
32155 REQUEST_DATA_STREAM(REQUEST_DATA_STREAM_DATA),
32156 REQUEST_EVENT(REQUEST_EVENT_DATA),
32157 RESOURCE_REQUEST(RESOURCE_REQUEST_DATA),
32158 RESPONSE_EVENT_ERROR(RESPONSE_EVENT_ERROR_DATA),
32159 SAFETY_ALLOWED_AREA(SAFETY_ALLOWED_AREA_DATA),
32160 SAFETY_SET_ALLOWED_AREA(SAFETY_SET_ALLOWED_AREA_DATA),
32161 SCALED_IMU(SCALED_IMU_DATA),
32162 SCALED_IMU2(SCALED_IMU2_DATA),
32163 SCALED_IMU3(SCALED_IMU3_DATA),
32164 SCALED_PRESSURE(SCALED_PRESSURE_DATA),
32165 SCALED_PRESSURE2(SCALED_PRESSURE2_DATA),
32166 SCALED_PRESSURE3(SCALED_PRESSURE3_DATA),
32167 SERIAL_CONTROL(SERIAL_CONTROL_DATA),
32168 SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA),
32169 SETUP_SIGNING(SETUP_SIGNING_DATA),
32170 SET_ACTUATOR_CONTROL_TARGET(SET_ACTUATOR_CONTROL_TARGET_DATA),
32171 SET_ATTITUDE_TARGET(SET_ATTITUDE_TARGET_DATA),
32172 SET_GPS_GLOBAL_ORIGIN(SET_GPS_GLOBAL_ORIGIN_DATA),
32173 SET_HOME_POSITION(SET_HOME_POSITION_DATA),
32174 SET_MODE(SET_MODE_DATA),
32175 SET_POSITION_TARGET_GLOBAL_INT(SET_POSITION_TARGET_GLOBAL_INT_DATA),
32176 SET_POSITION_TARGET_LOCAL_NED(SET_POSITION_TARGET_LOCAL_NED_DATA),
32177 SIM_STATE(SIM_STATE_DATA),
32178 SMART_BATTERY_INFO(SMART_BATTERY_INFO_DATA),
32179 STATUSTEXT(STATUSTEXT_DATA),
32180 STORAGE_INFORMATION(STORAGE_INFORMATION_DATA),
32181 SUPPORTED_TUNES(SUPPORTED_TUNES_DATA),
32182 SYSTEM_TIME(SYSTEM_TIME_DATA),
32183 SYS_STATUS(SYS_STATUS_DATA),
32184 TERRAIN_CHECK(TERRAIN_CHECK_DATA),
32185 TERRAIN_DATA(TERRAIN_DATA_DATA),
32186 TERRAIN_REPORT(TERRAIN_REPORT_DATA),
32187 TERRAIN_REQUEST(TERRAIN_REQUEST_DATA),
32188 TIMESYNC(TIMESYNC_DATA),
32189 TIME_ESTIMATE_TO_TARGET(TIME_ESTIMATE_TO_TARGET_DATA),
32190 TRAJECTORY_REPRESENTATION_BEZIER(TRAJECTORY_REPRESENTATION_BEZIER_DATA),
32191 TRAJECTORY_REPRESENTATION_WAYPOINTS(TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA),
32192 TUNNEL(TUNNEL_DATA),
32193 UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA),
32194 UAVCAN_NODE_STATUS(UAVCAN_NODE_STATUS_DATA),
32195 UAVIONIX_ADSB_GET(UAVIONIX_ADSB_GET_DATA),
32196 UAVIONIX_ADSB_OUT_CFG(UAVIONIX_ADSB_OUT_CFG_DATA),
32197 UAVIONIX_ADSB_OUT_CFG_FLIGHTID(UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA),
32198 UAVIONIX_ADSB_OUT_CFG_REGISTRATION(UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA),
32199 UAVIONIX_ADSB_OUT_CONTROL(UAVIONIX_ADSB_OUT_CONTROL_DATA),
32200 UAVIONIX_ADSB_OUT_DYNAMIC(UAVIONIX_ADSB_OUT_DYNAMIC_DATA),
32201 UAVIONIX_ADSB_OUT_STATUS(UAVIONIX_ADSB_OUT_STATUS_DATA),
32202 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA),
32203 UTM_GLOBAL_POSITION(UTM_GLOBAL_POSITION_DATA),
32204 V2_EXTENSION(V2_EXTENSION_DATA),
32205 VFR_HUD(VFR_HUD_DATA),
32206 VIBRATION(VIBRATION_DATA),
32207 VICON_POSITION_ESTIMATE(VICON_POSITION_ESTIMATE_DATA),
32208 VIDEO_STREAM_INFORMATION(VIDEO_STREAM_INFORMATION_DATA),
32209 VIDEO_STREAM_STATUS(VIDEO_STREAM_STATUS_DATA),
32210 VISION_POSITION_ESTIMATE(VISION_POSITION_ESTIMATE_DATA),
32211 VISION_SPEED_ESTIMATE(VISION_SPEED_ESTIMATE_DATA),
32212 WHEEL_DISTANCE(WHEEL_DISTANCE_DATA),
32213 WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA),
32214 WINCH_STATUS(WINCH_STATUS_DATA),
32215 WIND_COV(WIND_COV_DATA),
32216}
32217impl MavMessage {
32218 pub const fn all_ids() -> &'static [u32] {
32219 &[
32220 0u32, 1u32, 2u32, 4u32, 5u32, 6u32, 7u32, 8u32, 11u32, 20u32, 21u32, 22u32, 23u32,
32221 24u32, 25u32, 26u32, 27u32, 28u32, 29u32, 30u32, 31u32, 32u32, 33u32, 34u32, 35u32,
32222 36u32, 37u32, 38u32, 39u32, 40u32, 41u32, 42u32, 43u32, 44u32, 45u32, 46u32, 47u32,
32223 48u32, 49u32, 50u32, 51u32, 54u32, 55u32, 61u32, 62u32, 63u32, 64u32, 65u32, 66u32,
32224 67u32, 69u32, 70u32, 73u32, 74u32, 75u32, 76u32, 77u32, 80u32, 81u32, 82u32, 83u32,
32225 84u32, 85u32, 86u32, 87u32, 89u32, 90u32, 91u32, 92u32, 93u32, 100u32, 101u32, 102u32,
32226 103u32, 104u32, 105u32, 106u32, 107u32, 108u32, 109u32, 110u32, 111u32, 112u32, 113u32,
32227 114u32, 115u32, 116u32, 117u32, 118u32, 119u32, 120u32, 121u32, 122u32, 123u32, 124u32,
32228 125u32, 126u32, 127u32, 128u32, 129u32, 130u32, 131u32, 132u32, 133u32, 134u32, 135u32,
32229 136u32, 137u32, 138u32, 139u32, 140u32, 141u32, 142u32, 143u32, 144u32, 146u32, 147u32,
32230 148u32, 149u32, 162u32, 192u32, 225u32, 230u32, 231u32, 232u32, 233u32, 234u32, 235u32,
32231 241u32, 242u32, 243u32, 244u32, 245u32, 246u32, 247u32, 248u32, 249u32, 250u32, 251u32,
32232 252u32, 253u32, 254u32, 256u32, 257u32, 258u32, 259u32, 260u32, 261u32, 262u32, 263u32,
32233 264u32, 265u32, 266u32, 267u32, 268u32, 269u32, 270u32, 271u32, 275u32, 276u32, 277u32,
32234 280u32, 281u32, 282u32, 283u32, 284u32, 285u32, 286u32, 287u32, 288u32, 290u32, 291u32,
32235 299u32, 300u32, 301u32, 310u32, 311u32, 320u32, 321u32, 322u32, 323u32, 324u32, 330u32,
32236 331u32, 332u32, 333u32, 334u32, 335u32, 336u32, 339u32, 340u32, 350u32, 360u32, 370u32,
32237 371u32, 372u32, 373u32, 375u32, 380u32, 385u32, 386u32, 387u32, 388u32, 390u32, 395u32,
32238 396u32, 397u32, 400u32, 401u32, 410u32, 411u32, 412u32, 413u32, 435u32, 436u32, 437u32,
32239 440u32, 9000u32, 9005u32, 10001u32, 10002u32, 10003u32, 10004u32, 10005u32, 10006u32,
32240 10007u32, 10008u32, 12900u32, 12901u32, 12902u32, 12903u32, 12904u32, 12905u32,
32241 12915u32, 12918u32, 12919u32, 12920u32,
32242 ]
32243 }
32244}
32245impl Message for MavMessage {
32246 fn parse(
32247 version: MavlinkVersion,
32248 id: u32,
32249 payload: &[u8],
32250 ) -> Result<Self, ::mavlink_core::error::ParserError> {
32251 match id {
32252 ACTUATOR_CONTROL_TARGET_DATA::ID => {
32253 ACTUATOR_CONTROL_TARGET_DATA::deser(version, payload)
32254 .map(Self::ACTUATOR_CONTROL_TARGET)
32255 }
32256 ACTUATOR_OUTPUT_STATUS_DATA::ID => ACTUATOR_OUTPUT_STATUS_DATA::deser(version, payload)
32257 .map(Self::ACTUATOR_OUTPUT_STATUS),
32258 ADSB_VEHICLE_DATA::ID => {
32259 ADSB_VEHICLE_DATA::deser(version, payload).map(Self::ADSB_VEHICLE)
32260 }
32261 AIS_VESSEL_DATA::ID => AIS_VESSEL_DATA::deser(version, payload).map(Self::AIS_VESSEL),
32262 ALTITUDE_DATA::ID => ALTITUDE_DATA::deser(version, payload).map(Self::ALTITUDE),
32263 ATTITUDE_DATA::ID => ATTITUDE_DATA::deser(version, payload).map(Self::ATTITUDE),
32264 ATTITUDE_QUATERNION_DATA::ID => {
32265 ATTITUDE_QUATERNION_DATA::deser(version, payload).map(Self::ATTITUDE_QUATERNION)
32266 }
32267 ATTITUDE_QUATERNION_COV_DATA::ID => {
32268 ATTITUDE_QUATERNION_COV_DATA::deser(version, payload)
32269 .map(Self::ATTITUDE_QUATERNION_COV)
32270 }
32271 ATTITUDE_TARGET_DATA::ID => {
32272 ATTITUDE_TARGET_DATA::deser(version, payload).map(Self::ATTITUDE_TARGET)
32273 }
32274 ATT_POS_MOCAP_DATA::ID => {
32275 ATT_POS_MOCAP_DATA::deser(version, payload).map(Self::ATT_POS_MOCAP)
32276 }
32277 AUTH_KEY_DATA::ID => AUTH_KEY_DATA::deser(version, payload).map(Self::AUTH_KEY),
32278 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
32279 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::deser(version, payload)
32280 .map(Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE)
32281 }
32282 AUTOPILOT_VERSION_DATA::ID => {
32283 AUTOPILOT_VERSION_DATA::deser(version, payload).map(Self::AUTOPILOT_VERSION)
32284 }
32285 AVAILABLE_MODES_DATA::ID => {
32286 AVAILABLE_MODES_DATA::deser(version, payload).map(Self::AVAILABLE_MODES)
32287 }
32288 AVAILABLE_MODES_MONITOR_DATA::ID => {
32289 AVAILABLE_MODES_MONITOR_DATA::deser(version, payload)
32290 .map(Self::AVAILABLE_MODES_MONITOR)
32291 }
32292 BATTERY_INFO_DATA::ID => {
32293 BATTERY_INFO_DATA::deser(version, payload).map(Self::BATTERY_INFO)
32294 }
32295 BATTERY_STATUS_DATA::ID => {
32296 BATTERY_STATUS_DATA::deser(version, payload).map(Self::BATTERY_STATUS)
32297 }
32298 BUTTON_CHANGE_DATA::ID => {
32299 BUTTON_CHANGE_DATA::deser(version, payload).map(Self::BUTTON_CHANGE)
32300 }
32301 CAMERA_CAPTURE_STATUS_DATA::ID => {
32302 CAMERA_CAPTURE_STATUS_DATA::deser(version, payload).map(Self::CAMERA_CAPTURE_STATUS)
32303 }
32304 CAMERA_FOV_STATUS_DATA::ID => {
32305 CAMERA_FOV_STATUS_DATA::deser(version, payload).map(Self::CAMERA_FOV_STATUS)
32306 }
32307 CAMERA_IMAGE_CAPTURED_DATA::ID => {
32308 CAMERA_IMAGE_CAPTURED_DATA::deser(version, payload).map(Self::CAMERA_IMAGE_CAPTURED)
32309 }
32310 CAMERA_INFORMATION_DATA::ID => {
32311 CAMERA_INFORMATION_DATA::deser(version, payload).map(Self::CAMERA_INFORMATION)
32312 }
32313 CAMERA_SETTINGS_DATA::ID => {
32314 CAMERA_SETTINGS_DATA::deser(version, payload).map(Self::CAMERA_SETTINGS)
32315 }
32316 CAMERA_THERMAL_RANGE_DATA::ID => {
32317 CAMERA_THERMAL_RANGE_DATA::deser(version, payload).map(Self::CAMERA_THERMAL_RANGE)
32318 }
32319 CAMERA_TRACKING_GEO_STATUS_DATA::ID => {
32320 CAMERA_TRACKING_GEO_STATUS_DATA::deser(version, payload)
32321 .map(Self::CAMERA_TRACKING_GEO_STATUS)
32322 }
32323 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => {
32324 CAMERA_TRACKING_IMAGE_STATUS_DATA::deser(version, payload)
32325 .map(Self::CAMERA_TRACKING_IMAGE_STATUS)
32326 }
32327 CAMERA_TRIGGER_DATA::ID => {
32328 CAMERA_TRIGGER_DATA::deser(version, payload).map(Self::CAMERA_TRIGGER)
32329 }
32330 CANFD_FRAME_DATA::ID => {
32331 CANFD_FRAME_DATA::deser(version, payload).map(Self::CANFD_FRAME)
32332 }
32333 CAN_FILTER_MODIFY_DATA::ID => {
32334 CAN_FILTER_MODIFY_DATA::deser(version, payload).map(Self::CAN_FILTER_MODIFY)
32335 }
32336 CAN_FRAME_DATA::ID => CAN_FRAME_DATA::deser(version, payload).map(Self::CAN_FRAME),
32337 CELLULAR_CONFIG_DATA::ID => {
32338 CELLULAR_CONFIG_DATA::deser(version, payload).map(Self::CELLULAR_CONFIG)
32339 }
32340 CELLULAR_STATUS_DATA::ID => {
32341 CELLULAR_STATUS_DATA::deser(version, payload).map(Self::CELLULAR_STATUS)
32342 }
32343 CHANGE_OPERATOR_CONTROL_DATA::ID => {
32344 CHANGE_OPERATOR_CONTROL_DATA::deser(version, payload)
32345 .map(Self::CHANGE_OPERATOR_CONTROL)
32346 }
32347 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => {
32348 CHANGE_OPERATOR_CONTROL_ACK_DATA::deser(version, payload)
32349 .map(Self::CHANGE_OPERATOR_CONTROL_ACK)
32350 }
32351 COLLISION_DATA::ID => COLLISION_DATA::deser(version, payload).map(Self::COLLISION),
32352 COMMAND_ACK_DATA::ID => {
32353 COMMAND_ACK_DATA::deser(version, payload).map(Self::COMMAND_ACK)
32354 }
32355 COMMAND_CANCEL_DATA::ID => {
32356 COMMAND_CANCEL_DATA::deser(version, payload).map(Self::COMMAND_CANCEL)
32357 }
32358 COMMAND_INT_DATA::ID => {
32359 COMMAND_INT_DATA::deser(version, payload).map(Self::COMMAND_INT)
32360 }
32361 COMMAND_LONG_DATA::ID => {
32362 COMMAND_LONG_DATA::deser(version, payload).map(Self::COMMAND_LONG)
32363 }
32364 COMPONENT_INFORMATION_DATA::ID => {
32365 COMPONENT_INFORMATION_DATA::deser(version, payload).map(Self::COMPONENT_INFORMATION)
32366 }
32367 COMPONENT_INFORMATION_BASIC_DATA::ID => {
32368 COMPONENT_INFORMATION_BASIC_DATA::deser(version, payload)
32369 .map(Self::COMPONENT_INFORMATION_BASIC)
32370 }
32371 COMPONENT_METADATA_DATA::ID => {
32372 COMPONENT_METADATA_DATA::deser(version, payload).map(Self::COMPONENT_METADATA)
32373 }
32374 CONTROL_SYSTEM_STATE_DATA::ID => {
32375 CONTROL_SYSTEM_STATE_DATA::deser(version, payload).map(Self::CONTROL_SYSTEM_STATE)
32376 }
32377 CURRENT_EVENT_SEQUENCE_DATA::ID => CURRENT_EVENT_SEQUENCE_DATA::deser(version, payload)
32378 .map(Self::CURRENT_EVENT_SEQUENCE),
32379 CURRENT_MODE_DATA::ID => {
32380 CURRENT_MODE_DATA::deser(version, payload).map(Self::CURRENT_MODE)
32381 }
32382 DATA_STREAM_DATA::ID => {
32383 DATA_STREAM_DATA::deser(version, payload).map(Self::DATA_STREAM)
32384 }
32385 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => {
32386 DATA_TRANSMISSION_HANDSHAKE_DATA::deser(version, payload)
32387 .map(Self::DATA_TRANSMISSION_HANDSHAKE)
32388 }
32389 DEBUG_DATA::ID => DEBUG_DATA::deser(version, payload).map(Self::DEBUG),
32390 DEBUG_FLOAT_ARRAY_DATA::ID => {
32391 DEBUG_FLOAT_ARRAY_DATA::deser(version, payload).map(Self::DEBUG_FLOAT_ARRAY)
32392 }
32393 DEBUG_VECT_DATA::ID => DEBUG_VECT_DATA::deser(version, payload).map(Self::DEBUG_VECT),
32394 DISTANCE_SENSOR_DATA::ID => {
32395 DISTANCE_SENSOR_DATA::deser(version, payload).map(Self::DISTANCE_SENSOR)
32396 }
32397 EFI_STATUS_DATA::ID => EFI_STATUS_DATA::deser(version, payload).map(Self::EFI_STATUS),
32398 ENCAPSULATED_DATA_DATA::ID => {
32399 ENCAPSULATED_DATA_DATA::deser(version, payload).map(Self::ENCAPSULATED_DATA)
32400 }
32401 ESC_INFO_DATA::ID => ESC_INFO_DATA::deser(version, payload).map(Self::ESC_INFO),
32402 ESC_STATUS_DATA::ID => ESC_STATUS_DATA::deser(version, payload).map(Self::ESC_STATUS),
32403 ESTIMATOR_STATUS_DATA::ID => {
32404 ESTIMATOR_STATUS_DATA::deser(version, payload).map(Self::ESTIMATOR_STATUS)
32405 }
32406 EVENT_DATA::ID => EVENT_DATA::deser(version, payload).map(Self::EVENT),
32407 EXTENDED_SYS_STATE_DATA::ID => {
32408 EXTENDED_SYS_STATE_DATA::deser(version, payload).map(Self::EXTENDED_SYS_STATE)
32409 }
32410 FENCE_STATUS_DATA::ID => {
32411 FENCE_STATUS_DATA::deser(version, payload).map(Self::FENCE_STATUS)
32412 }
32413 FILE_TRANSFER_PROTOCOL_DATA::ID => FILE_TRANSFER_PROTOCOL_DATA::deser(version, payload)
32414 .map(Self::FILE_TRANSFER_PROTOCOL),
32415 FLIGHT_INFORMATION_DATA::ID => {
32416 FLIGHT_INFORMATION_DATA::deser(version, payload).map(Self::FLIGHT_INFORMATION)
32417 }
32418 FOLLOW_TARGET_DATA::ID => {
32419 FOLLOW_TARGET_DATA::deser(version, payload).map(Self::FOLLOW_TARGET)
32420 }
32421 FUEL_STATUS_DATA::ID => {
32422 FUEL_STATUS_DATA::deser(version, payload).map(Self::FUEL_STATUS)
32423 }
32424 GENERATOR_STATUS_DATA::ID => {
32425 GENERATOR_STATUS_DATA::deser(version, payload).map(Self::GENERATOR_STATUS)
32426 }
32427 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => {
32428 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::deser(version, payload)
32429 .map(Self::GIMBAL_DEVICE_ATTITUDE_STATUS)
32430 }
32431 GIMBAL_DEVICE_INFORMATION_DATA::ID => {
32432 GIMBAL_DEVICE_INFORMATION_DATA::deser(version, payload)
32433 .map(Self::GIMBAL_DEVICE_INFORMATION)
32434 }
32435 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => {
32436 GIMBAL_DEVICE_SET_ATTITUDE_DATA::deser(version, payload)
32437 .map(Self::GIMBAL_DEVICE_SET_ATTITUDE)
32438 }
32439 GIMBAL_MANAGER_INFORMATION_DATA::ID => {
32440 GIMBAL_MANAGER_INFORMATION_DATA::deser(version, payload)
32441 .map(Self::GIMBAL_MANAGER_INFORMATION)
32442 }
32443 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => {
32444 GIMBAL_MANAGER_SET_ATTITUDE_DATA::deser(version, payload)
32445 .map(Self::GIMBAL_MANAGER_SET_ATTITUDE)
32446 }
32447 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
32448 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::deser(version, payload)
32449 .map(Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL)
32450 }
32451 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => {
32452 GIMBAL_MANAGER_SET_PITCHYAW_DATA::deser(version, payload)
32453 .map(Self::GIMBAL_MANAGER_SET_PITCHYAW)
32454 }
32455 GIMBAL_MANAGER_STATUS_DATA::ID => {
32456 GIMBAL_MANAGER_STATUS_DATA::deser(version, payload).map(Self::GIMBAL_MANAGER_STATUS)
32457 }
32458 GLOBAL_POSITION_INT_DATA::ID => {
32459 GLOBAL_POSITION_INT_DATA::deser(version, payload).map(Self::GLOBAL_POSITION_INT)
32460 }
32461 GLOBAL_POSITION_INT_COV_DATA::ID => {
32462 GLOBAL_POSITION_INT_COV_DATA::deser(version, payload)
32463 .map(Self::GLOBAL_POSITION_INT_COV)
32464 }
32465 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
32466 GLOBAL_VISION_POSITION_ESTIMATE_DATA::deser(version, payload)
32467 .map(Self::GLOBAL_VISION_POSITION_ESTIMATE)
32468 }
32469 GPS2_RAW_DATA::ID => GPS2_RAW_DATA::deser(version, payload).map(Self::GPS2_RAW),
32470 GPS2_RTK_DATA::ID => GPS2_RTK_DATA::deser(version, payload).map(Self::GPS2_RTK),
32471 GPS_GLOBAL_ORIGIN_DATA::ID => {
32472 GPS_GLOBAL_ORIGIN_DATA::deser(version, payload).map(Self::GPS_GLOBAL_ORIGIN)
32473 }
32474 GPS_INJECT_DATA_DATA::ID => {
32475 GPS_INJECT_DATA_DATA::deser(version, payload).map(Self::GPS_INJECT_DATA)
32476 }
32477 GPS_INPUT_DATA::ID => GPS_INPUT_DATA::deser(version, payload).map(Self::GPS_INPUT),
32478 GPS_RAW_INT_DATA::ID => {
32479 GPS_RAW_INT_DATA::deser(version, payload).map(Self::GPS_RAW_INT)
32480 }
32481 GPS_RTCM_DATA_DATA::ID => {
32482 GPS_RTCM_DATA_DATA::deser(version, payload).map(Self::GPS_RTCM_DATA)
32483 }
32484 GPS_RTK_DATA::ID => GPS_RTK_DATA::deser(version, payload).map(Self::GPS_RTK),
32485 GPS_STATUS_DATA::ID => GPS_STATUS_DATA::deser(version, payload).map(Self::GPS_STATUS),
32486 HEARTBEAT_DATA::ID => HEARTBEAT_DATA::deser(version, payload).map(Self::HEARTBEAT),
32487 HIGHRES_IMU_DATA::ID => {
32488 HIGHRES_IMU_DATA::deser(version, payload).map(Self::HIGHRES_IMU)
32489 }
32490 HIGH_LATENCY_DATA::ID => {
32491 HIGH_LATENCY_DATA::deser(version, payload).map(Self::HIGH_LATENCY)
32492 }
32493 HIGH_LATENCY2_DATA::ID => {
32494 HIGH_LATENCY2_DATA::deser(version, payload).map(Self::HIGH_LATENCY2)
32495 }
32496 HIL_ACTUATOR_CONTROLS_DATA::ID => {
32497 HIL_ACTUATOR_CONTROLS_DATA::deser(version, payload).map(Self::HIL_ACTUATOR_CONTROLS)
32498 }
32499 HIL_CONTROLS_DATA::ID => {
32500 HIL_CONTROLS_DATA::deser(version, payload).map(Self::HIL_CONTROLS)
32501 }
32502 HIL_GPS_DATA::ID => HIL_GPS_DATA::deser(version, payload).map(Self::HIL_GPS),
32503 HIL_OPTICAL_FLOW_DATA::ID => {
32504 HIL_OPTICAL_FLOW_DATA::deser(version, payload).map(Self::HIL_OPTICAL_FLOW)
32505 }
32506 HIL_RC_INPUTS_RAW_DATA::ID => {
32507 HIL_RC_INPUTS_RAW_DATA::deser(version, payload).map(Self::HIL_RC_INPUTS_RAW)
32508 }
32509 HIL_SENSOR_DATA::ID => HIL_SENSOR_DATA::deser(version, payload).map(Self::HIL_SENSOR),
32510 HIL_STATE_DATA::ID => HIL_STATE_DATA::deser(version, payload).map(Self::HIL_STATE),
32511 HIL_STATE_QUATERNION_DATA::ID => {
32512 HIL_STATE_QUATERNION_DATA::deser(version, payload).map(Self::HIL_STATE_QUATERNION)
32513 }
32514 HOME_POSITION_DATA::ID => {
32515 HOME_POSITION_DATA::deser(version, payload).map(Self::HOME_POSITION)
32516 }
32517 HYGROMETER_SENSOR_DATA::ID => {
32518 HYGROMETER_SENSOR_DATA::deser(version, payload).map(Self::HYGROMETER_SENSOR)
32519 }
32520 ILLUMINATOR_STATUS_DATA::ID => {
32521 ILLUMINATOR_STATUS_DATA::deser(version, payload).map(Self::ILLUMINATOR_STATUS)
32522 }
32523 ISBD_LINK_STATUS_DATA::ID => {
32524 ISBD_LINK_STATUS_DATA::deser(version, payload).map(Self::ISBD_LINK_STATUS)
32525 }
32526 LANDING_TARGET_DATA::ID => {
32527 LANDING_TARGET_DATA::deser(version, payload).map(Self::LANDING_TARGET)
32528 }
32529 LINK_NODE_STATUS_DATA::ID => {
32530 LINK_NODE_STATUS_DATA::deser(version, payload).map(Self::LINK_NODE_STATUS)
32531 }
32532 LOCAL_POSITION_NED_DATA::ID => {
32533 LOCAL_POSITION_NED_DATA::deser(version, payload).map(Self::LOCAL_POSITION_NED)
32534 }
32535 LOCAL_POSITION_NED_COV_DATA::ID => LOCAL_POSITION_NED_COV_DATA::deser(version, payload)
32536 .map(Self::LOCAL_POSITION_NED_COV),
32537 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
32538 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::deser(version, payload)
32539 .map(Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET)
32540 }
32541 LOGGING_ACK_DATA::ID => {
32542 LOGGING_ACK_DATA::deser(version, payload).map(Self::LOGGING_ACK)
32543 }
32544 LOGGING_DATA_DATA::ID => {
32545 LOGGING_DATA_DATA::deser(version, payload).map(Self::LOGGING_DATA)
32546 }
32547 LOGGING_DATA_ACKED_DATA::ID => {
32548 LOGGING_DATA_ACKED_DATA::deser(version, payload).map(Self::LOGGING_DATA_ACKED)
32549 }
32550 LOG_DATA_DATA::ID => LOG_DATA_DATA::deser(version, payload).map(Self::LOG_DATA),
32551 LOG_ENTRY_DATA::ID => LOG_ENTRY_DATA::deser(version, payload).map(Self::LOG_ENTRY),
32552 LOG_ERASE_DATA::ID => LOG_ERASE_DATA::deser(version, payload).map(Self::LOG_ERASE),
32553 LOG_REQUEST_DATA_DATA::ID => {
32554 LOG_REQUEST_DATA_DATA::deser(version, payload).map(Self::LOG_REQUEST_DATA)
32555 }
32556 LOG_REQUEST_END_DATA::ID => {
32557 LOG_REQUEST_END_DATA::deser(version, payload).map(Self::LOG_REQUEST_END)
32558 }
32559 LOG_REQUEST_LIST_DATA::ID => {
32560 LOG_REQUEST_LIST_DATA::deser(version, payload).map(Self::LOG_REQUEST_LIST)
32561 }
32562 MAG_CAL_REPORT_DATA::ID => {
32563 MAG_CAL_REPORT_DATA::deser(version, payload).map(Self::MAG_CAL_REPORT)
32564 }
32565 MANUAL_CONTROL_DATA::ID => {
32566 MANUAL_CONTROL_DATA::deser(version, payload).map(Self::MANUAL_CONTROL)
32567 }
32568 MANUAL_SETPOINT_DATA::ID => {
32569 MANUAL_SETPOINT_DATA::deser(version, payload).map(Self::MANUAL_SETPOINT)
32570 }
32571 MEMORY_VECT_DATA::ID => {
32572 MEMORY_VECT_DATA::deser(version, payload).map(Self::MEMORY_VECT)
32573 }
32574 MESSAGE_INTERVAL_DATA::ID => {
32575 MESSAGE_INTERVAL_DATA::deser(version, payload).map(Self::MESSAGE_INTERVAL)
32576 }
32577 MISSION_ACK_DATA::ID => {
32578 MISSION_ACK_DATA::deser(version, payload).map(Self::MISSION_ACK)
32579 }
32580 MISSION_CLEAR_ALL_DATA::ID => {
32581 MISSION_CLEAR_ALL_DATA::deser(version, payload).map(Self::MISSION_CLEAR_ALL)
32582 }
32583 MISSION_COUNT_DATA::ID => {
32584 MISSION_COUNT_DATA::deser(version, payload).map(Self::MISSION_COUNT)
32585 }
32586 MISSION_CURRENT_DATA::ID => {
32587 MISSION_CURRENT_DATA::deser(version, payload).map(Self::MISSION_CURRENT)
32588 }
32589 MISSION_ITEM_DATA::ID => {
32590 MISSION_ITEM_DATA::deser(version, payload).map(Self::MISSION_ITEM)
32591 }
32592 MISSION_ITEM_INT_DATA::ID => {
32593 MISSION_ITEM_INT_DATA::deser(version, payload).map(Self::MISSION_ITEM_INT)
32594 }
32595 MISSION_ITEM_REACHED_DATA::ID => {
32596 MISSION_ITEM_REACHED_DATA::deser(version, payload).map(Self::MISSION_ITEM_REACHED)
32597 }
32598 MISSION_REQUEST_DATA::ID => {
32599 MISSION_REQUEST_DATA::deser(version, payload).map(Self::MISSION_REQUEST)
32600 }
32601 MISSION_REQUEST_INT_DATA::ID => {
32602 MISSION_REQUEST_INT_DATA::deser(version, payload).map(Self::MISSION_REQUEST_INT)
32603 }
32604 MISSION_REQUEST_LIST_DATA::ID => {
32605 MISSION_REQUEST_LIST_DATA::deser(version, payload).map(Self::MISSION_REQUEST_LIST)
32606 }
32607 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => {
32608 MISSION_REQUEST_PARTIAL_LIST_DATA::deser(version, payload)
32609 .map(Self::MISSION_REQUEST_PARTIAL_LIST)
32610 }
32611 MISSION_SET_CURRENT_DATA::ID => {
32612 MISSION_SET_CURRENT_DATA::deser(version, payload).map(Self::MISSION_SET_CURRENT)
32613 }
32614 MISSION_WRITE_PARTIAL_LIST_DATA::ID => {
32615 MISSION_WRITE_PARTIAL_LIST_DATA::deser(version, payload)
32616 .map(Self::MISSION_WRITE_PARTIAL_LIST)
32617 }
32618 MOUNT_ORIENTATION_DATA::ID => {
32619 MOUNT_ORIENTATION_DATA::deser(version, payload).map(Self::MOUNT_ORIENTATION)
32620 }
32621 NAMED_VALUE_FLOAT_DATA::ID => {
32622 NAMED_VALUE_FLOAT_DATA::deser(version, payload).map(Self::NAMED_VALUE_FLOAT)
32623 }
32624 NAMED_VALUE_INT_DATA::ID => {
32625 NAMED_VALUE_INT_DATA::deser(version, payload).map(Self::NAMED_VALUE_INT)
32626 }
32627 NAV_CONTROLLER_OUTPUT_DATA::ID => {
32628 NAV_CONTROLLER_OUTPUT_DATA::deser(version, payload).map(Self::NAV_CONTROLLER_OUTPUT)
32629 }
32630 OBSTACLE_DISTANCE_DATA::ID => {
32631 OBSTACLE_DISTANCE_DATA::deser(version, payload).map(Self::OBSTACLE_DISTANCE)
32632 }
32633 ODOMETRY_DATA::ID => ODOMETRY_DATA::deser(version, payload).map(Self::ODOMETRY),
32634 ONBOARD_COMPUTER_STATUS_DATA::ID => {
32635 ONBOARD_COMPUTER_STATUS_DATA::deser(version, payload)
32636 .map(Self::ONBOARD_COMPUTER_STATUS)
32637 }
32638 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => {
32639 OPEN_DRONE_ID_ARM_STATUS_DATA::deser(version, payload)
32640 .map(Self::OPEN_DRONE_ID_ARM_STATUS)
32641 }
32642 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => {
32643 OPEN_DRONE_ID_AUTHENTICATION_DATA::deser(version, payload)
32644 .map(Self::OPEN_DRONE_ID_AUTHENTICATION)
32645 }
32646 OPEN_DRONE_ID_BASIC_ID_DATA::ID => OPEN_DRONE_ID_BASIC_ID_DATA::deser(version, payload)
32647 .map(Self::OPEN_DRONE_ID_BASIC_ID),
32648 OPEN_DRONE_ID_LOCATION_DATA::ID => OPEN_DRONE_ID_LOCATION_DATA::deser(version, payload)
32649 .map(Self::OPEN_DRONE_ID_LOCATION),
32650 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => {
32651 OPEN_DRONE_ID_MESSAGE_PACK_DATA::deser(version, payload)
32652 .map(Self::OPEN_DRONE_ID_MESSAGE_PACK)
32653 }
32654 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => {
32655 OPEN_DRONE_ID_OPERATOR_ID_DATA::deser(version, payload)
32656 .map(Self::OPEN_DRONE_ID_OPERATOR_ID)
32657 }
32658 OPEN_DRONE_ID_SELF_ID_DATA::ID => {
32659 OPEN_DRONE_ID_SELF_ID_DATA::deser(version, payload).map(Self::OPEN_DRONE_ID_SELF_ID)
32660 }
32661 OPEN_DRONE_ID_SYSTEM_DATA::ID => {
32662 OPEN_DRONE_ID_SYSTEM_DATA::deser(version, payload).map(Self::OPEN_DRONE_ID_SYSTEM)
32663 }
32664 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => {
32665 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::deser(version, payload)
32666 .map(Self::OPEN_DRONE_ID_SYSTEM_UPDATE)
32667 }
32668 OPTICAL_FLOW_DATA::ID => {
32669 OPTICAL_FLOW_DATA::deser(version, payload).map(Self::OPTICAL_FLOW)
32670 }
32671 OPTICAL_FLOW_RAD_DATA::ID => {
32672 OPTICAL_FLOW_RAD_DATA::deser(version, payload).map(Self::OPTICAL_FLOW_RAD)
32673 }
32674 ORBIT_EXECUTION_STATUS_DATA::ID => ORBIT_EXECUTION_STATUS_DATA::deser(version, payload)
32675 .map(Self::ORBIT_EXECUTION_STATUS),
32676 PARAM_EXT_ACK_DATA::ID => {
32677 PARAM_EXT_ACK_DATA::deser(version, payload).map(Self::PARAM_EXT_ACK)
32678 }
32679 PARAM_EXT_REQUEST_LIST_DATA::ID => PARAM_EXT_REQUEST_LIST_DATA::deser(version, payload)
32680 .map(Self::PARAM_EXT_REQUEST_LIST),
32681 PARAM_EXT_REQUEST_READ_DATA::ID => PARAM_EXT_REQUEST_READ_DATA::deser(version, payload)
32682 .map(Self::PARAM_EXT_REQUEST_READ),
32683 PARAM_EXT_SET_DATA::ID => {
32684 PARAM_EXT_SET_DATA::deser(version, payload).map(Self::PARAM_EXT_SET)
32685 }
32686 PARAM_EXT_VALUE_DATA::ID => {
32687 PARAM_EXT_VALUE_DATA::deser(version, payload).map(Self::PARAM_EXT_VALUE)
32688 }
32689 PARAM_MAP_RC_DATA::ID => {
32690 PARAM_MAP_RC_DATA::deser(version, payload).map(Self::PARAM_MAP_RC)
32691 }
32692 PARAM_REQUEST_LIST_DATA::ID => {
32693 PARAM_REQUEST_LIST_DATA::deser(version, payload).map(Self::PARAM_REQUEST_LIST)
32694 }
32695 PARAM_REQUEST_READ_DATA::ID => {
32696 PARAM_REQUEST_READ_DATA::deser(version, payload).map(Self::PARAM_REQUEST_READ)
32697 }
32698 PARAM_SET_DATA::ID => PARAM_SET_DATA::deser(version, payload).map(Self::PARAM_SET),
32699 PARAM_VALUE_DATA::ID => {
32700 PARAM_VALUE_DATA::deser(version, payload).map(Self::PARAM_VALUE)
32701 }
32702 PING_DATA::ID => PING_DATA::deser(version, payload).map(Self::PING),
32703 PLAY_TUNE_DATA::ID => PLAY_TUNE_DATA::deser(version, payload).map(Self::PLAY_TUNE),
32704 PLAY_TUNE_V2_DATA::ID => {
32705 PLAY_TUNE_V2_DATA::deser(version, payload).map(Self::PLAY_TUNE_V2)
32706 }
32707 POSITION_TARGET_GLOBAL_INT_DATA::ID => {
32708 POSITION_TARGET_GLOBAL_INT_DATA::deser(version, payload)
32709 .map(Self::POSITION_TARGET_GLOBAL_INT)
32710 }
32711 POSITION_TARGET_LOCAL_NED_DATA::ID => {
32712 POSITION_TARGET_LOCAL_NED_DATA::deser(version, payload)
32713 .map(Self::POSITION_TARGET_LOCAL_NED)
32714 }
32715 POWER_STATUS_DATA::ID => {
32716 POWER_STATUS_DATA::deser(version, payload).map(Self::POWER_STATUS)
32717 }
32718 PROTOCOL_VERSION_DATA::ID => {
32719 PROTOCOL_VERSION_DATA::deser(version, payload).map(Self::PROTOCOL_VERSION)
32720 }
32721 RADIO_STATUS_DATA::ID => {
32722 RADIO_STATUS_DATA::deser(version, payload).map(Self::RADIO_STATUS)
32723 }
32724 RAW_IMU_DATA::ID => RAW_IMU_DATA::deser(version, payload).map(Self::RAW_IMU),
32725 RAW_PRESSURE_DATA::ID => {
32726 RAW_PRESSURE_DATA::deser(version, payload).map(Self::RAW_PRESSURE)
32727 }
32728 RAW_RPM_DATA::ID => RAW_RPM_DATA::deser(version, payload).map(Self::RAW_RPM),
32729 RC_CHANNELS_DATA::ID => {
32730 RC_CHANNELS_DATA::deser(version, payload).map(Self::RC_CHANNELS)
32731 }
32732 RC_CHANNELS_OVERRIDE_DATA::ID => {
32733 RC_CHANNELS_OVERRIDE_DATA::deser(version, payload).map(Self::RC_CHANNELS_OVERRIDE)
32734 }
32735 RC_CHANNELS_RAW_DATA::ID => {
32736 RC_CHANNELS_RAW_DATA::deser(version, payload).map(Self::RC_CHANNELS_RAW)
32737 }
32738 RC_CHANNELS_SCALED_DATA::ID => {
32739 RC_CHANNELS_SCALED_DATA::deser(version, payload).map(Self::RC_CHANNELS_SCALED)
32740 }
32741 REQUEST_DATA_STREAM_DATA::ID => {
32742 REQUEST_DATA_STREAM_DATA::deser(version, payload).map(Self::REQUEST_DATA_STREAM)
32743 }
32744 REQUEST_EVENT_DATA::ID => {
32745 REQUEST_EVENT_DATA::deser(version, payload).map(Self::REQUEST_EVENT)
32746 }
32747 RESOURCE_REQUEST_DATA::ID => {
32748 RESOURCE_REQUEST_DATA::deser(version, payload).map(Self::RESOURCE_REQUEST)
32749 }
32750 RESPONSE_EVENT_ERROR_DATA::ID => {
32751 RESPONSE_EVENT_ERROR_DATA::deser(version, payload).map(Self::RESPONSE_EVENT_ERROR)
32752 }
32753 SAFETY_ALLOWED_AREA_DATA::ID => {
32754 SAFETY_ALLOWED_AREA_DATA::deser(version, payload).map(Self::SAFETY_ALLOWED_AREA)
32755 }
32756 SAFETY_SET_ALLOWED_AREA_DATA::ID => {
32757 SAFETY_SET_ALLOWED_AREA_DATA::deser(version, payload)
32758 .map(Self::SAFETY_SET_ALLOWED_AREA)
32759 }
32760 SCALED_IMU_DATA::ID => SCALED_IMU_DATA::deser(version, payload).map(Self::SCALED_IMU),
32761 SCALED_IMU2_DATA::ID => {
32762 SCALED_IMU2_DATA::deser(version, payload).map(Self::SCALED_IMU2)
32763 }
32764 SCALED_IMU3_DATA::ID => {
32765 SCALED_IMU3_DATA::deser(version, payload).map(Self::SCALED_IMU3)
32766 }
32767 SCALED_PRESSURE_DATA::ID => {
32768 SCALED_PRESSURE_DATA::deser(version, payload).map(Self::SCALED_PRESSURE)
32769 }
32770 SCALED_PRESSURE2_DATA::ID => {
32771 SCALED_PRESSURE2_DATA::deser(version, payload).map(Self::SCALED_PRESSURE2)
32772 }
32773 SCALED_PRESSURE3_DATA::ID => {
32774 SCALED_PRESSURE3_DATA::deser(version, payload).map(Self::SCALED_PRESSURE3)
32775 }
32776 SERIAL_CONTROL_DATA::ID => {
32777 SERIAL_CONTROL_DATA::deser(version, payload).map(Self::SERIAL_CONTROL)
32778 }
32779 SERVO_OUTPUT_RAW_DATA::ID => {
32780 SERVO_OUTPUT_RAW_DATA::deser(version, payload).map(Self::SERVO_OUTPUT_RAW)
32781 }
32782 SETUP_SIGNING_DATA::ID => {
32783 SETUP_SIGNING_DATA::deser(version, payload).map(Self::SETUP_SIGNING)
32784 }
32785 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => {
32786 SET_ACTUATOR_CONTROL_TARGET_DATA::deser(version, payload)
32787 .map(Self::SET_ACTUATOR_CONTROL_TARGET)
32788 }
32789 SET_ATTITUDE_TARGET_DATA::ID => {
32790 SET_ATTITUDE_TARGET_DATA::deser(version, payload).map(Self::SET_ATTITUDE_TARGET)
32791 }
32792 SET_GPS_GLOBAL_ORIGIN_DATA::ID => {
32793 SET_GPS_GLOBAL_ORIGIN_DATA::deser(version, payload).map(Self::SET_GPS_GLOBAL_ORIGIN)
32794 }
32795 SET_HOME_POSITION_DATA::ID => {
32796 SET_HOME_POSITION_DATA::deser(version, payload).map(Self::SET_HOME_POSITION)
32797 }
32798 SET_MODE_DATA::ID => SET_MODE_DATA::deser(version, payload).map(Self::SET_MODE),
32799 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => {
32800 SET_POSITION_TARGET_GLOBAL_INT_DATA::deser(version, payload)
32801 .map(Self::SET_POSITION_TARGET_GLOBAL_INT)
32802 }
32803 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => {
32804 SET_POSITION_TARGET_LOCAL_NED_DATA::deser(version, payload)
32805 .map(Self::SET_POSITION_TARGET_LOCAL_NED)
32806 }
32807 SIM_STATE_DATA::ID => SIM_STATE_DATA::deser(version, payload).map(Self::SIM_STATE),
32808 SMART_BATTERY_INFO_DATA::ID => {
32809 SMART_BATTERY_INFO_DATA::deser(version, payload).map(Self::SMART_BATTERY_INFO)
32810 }
32811 STATUSTEXT_DATA::ID => STATUSTEXT_DATA::deser(version, payload).map(Self::STATUSTEXT),
32812 STORAGE_INFORMATION_DATA::ID => {
32813 STORAGE_INFORMATION_DATA::deser(version, payload).map(Self::STORAGE_INFORMATION)
32814 }
32815 SUPPORTED_TUNES_DATA::ID => {
32816 SUPPORTED_TUNES_DATA::deser(version, payload).map(Self::SUPPORTED_TUNES)
32817 }
32818 SYSTEM_TIME_DATA::ID => {
32819 SYSTEM_TIME_DATA::deser(version, payload).map(Self::SYSTEM_TIME)
32820 }
32821 SYS_STATUS_DATA::ID => SYS_STATUS_DATA::deser(version, payload).map(Self::SYS_STATUS),
32822 TERRAIN_CHECK_DATA::ID => {
32823 TERRAIN_CHECK_DATA::deser(version, payload).map(Self::TERRAIN_CHECK)
32824 }
32825 TERRAIN_DATA_DATA::ID => {
32826 TERRAIN_DATA_DATA::deser(version, payload).map(Self::TERRAIN_DATA)
32827 }
32828 TERRAIN_REPORT_DATA::ID => {
32829 TERRAIN_REPORT_DATA::deser(version, payload).map(Self::TERRAIN_REPORT)
32830 }
32831 TERRAIN_REQUEST_DATA::ID => {
32832 TERRAIN_REQUEST_DATA::deser(version, payload).map(Self::TERRAIN_REQUEST)
32833 }
32834 TIMESYNC_DATA::ID => TIMESYNC_DATA::deser(version, payload).map(Self::TIMESYNC),
32835 TIME_ESTIMATE_TO_TARGET_DATA::ID => {
32836 TIME_ESTIMATE_TO_TARGET_DATA::deser(version, payload)
32837 .map(Self::TIME_ESTIMATE_TO_TARGET)
32838 }
32839 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
32840 TRAJECTORY_REPRESENTATION_BEZIER_DATA::deser(version, payload)
32841 .map(Self::TRAJECTORY_REPRESENTATION_BEZIER)
32842 }
32843 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
32844 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::deser(version, payload)
32845 .map(Self::TRAJECTORY_REPRESENTATION_WAYPOINTS)
32846 }
32847 TUNNEL_DATA::ID => TUNNEL_DATA::deser(version, payload).map(Self::TUNNEL),
32848 UAVCAN_NODE_INFO_DATA::ID => {
32849 UAVCAN_NODE_INFO_DATA::deser(version, payload).map(Self::UAVCAN_NODE_INFO)
32850 }
32851 UAVCAN_NODE_STATUS_DATA::ID => {
32852 UAVCAN_NODE_STATUS_DATA::deser(version, payload).map(Self::UAVCAN_NODE_STATUS)
32853 }
32854 UAVIONIX_ADSB_GET_DATA::ID => {
32855 UAVIONIX_ADSB_GET_DATA::deser(version, payload).map(Self::UAVIONIX_ADSB_GET)
32856 }
32857 UAVIONIX_ADSB_OUT_CFG_DATA::ID => {
32858 UAVIONIX_ADSB_OUT_CFG_DATA::deser(version, payload).map(Self::UAVIONIX_ADSB_OUT_CFG)
32859 }
32860 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::ID => {
32861 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::deser(version, payload)
32862 .map(Self::UAVIONIX_ADSB_OUT_CFG_FLIGHTID)
32863 }
32864 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::ID => {
32865 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::deser(version, payload)
32866 .map(Self::UAVIONIX_ADSB_OUT_CFG_REGISTRATION)
32867 }
32868 UAVIONIX_ADSB_OUT_CONTROL_DATA::ID => {
32869 UAVIONIX_ADSB_OUT_CONTROL_DATA::deser(version, payload)
32870 .map(Self::UAVIONIX_ADSB_OUT_CONTROL)
32871 }
32872 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::ID => {
32873 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::deser(version, payload)
32874 .map(Self::UAVIONIX_ADSB_OUT_DYNAMIC)
32875 }
32876 UAVIONIX_ADSB_OUT_STATUS_DATA::ID => {
32877 UAVIONIX_ADSB_OUT_STATUS_DATA::deser(version, payload)
32878 .map(Self::UAVIONIX_ADSB_OUT_STATUS)
32879 }
32880 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::ID => {
32881 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::deser(version, payload)
32882 .map(Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT)
32883 }
32884 UTM_GLOBAL_POSITION_DATA::ID => {
32885 UTM_GLOBAL_POSITION_DATA::deser(version, payload).map(Self::UTM_GLOBAL_POSITION)
32886 }
32887 V2_EXTENSION_DATA::ID => {
32888 V2_EXTENSION_DATA::deser(version, payload).map(Self::V2_EXTENSION)
32889 }
32890 VFR_HUD_DATA::ID => VFR_HUD_DATA::deser(version, payload).map(Self::VFR_HUD),
32891 VIBRATION_DATA::ID => VIBRATION_DATA::deser(version, payload).map(Self::VIBRATION),
32892 VICON_POSITION_ESTIMATE_DATA::ID => {
32893 VICON_POSITION_ESTIMATE_DATA::deser(version, payload)
32894 .map(Self::VICON_POSITION_ESTIMATE)
32895 }
32896 VIDEO_STREAM_INFORMATION_DATA::ID => {
32897 VIDEO_STREAM_INFORMATION_DATA::deser(version, payload)
32898 .map(Self::VIDEO_STREAM_INFORMATION)
32899 }
32900 VIDEO_STREAM_STATUS_DATA::ID => {
32901 VIDEO_STREAM_STATUS_DATA::deser(version, payload).map(Self::VIDEO_STREAM_STATUS)
32902 }
32903 VISION_POSITION_ESTIMATE_DATA::ID => {
32904 VISION_POSITION_ESTIMATE_DATA::deser(version, payload)
32905 .map(Self::VISION_POSITION_ESTIMATE)
32906 }
32907 VISION_SPEED_ESTIMATE_DATA::ID => {
32908 VISION_SPEED_ESTIMATE_DATA::deser(version, payload).map(Self::VISION_SPEED_ESTIMATE)
32909 }
32910 WHEEL_DISTANCE_DATA::ID => {
32911 WHEEL_DISTANCE_DATA::deser(version, payload).map(Self::WHEEL_DISTANCE)
32912 }
32913 WIFI_CONFIG_AP_DATA::ID => {
32914 WIFI_CONFIG_AP_DATA::deser(version, payload).map(Self::WIFI_CONFIG_AP)
32915 }
32916 WINCH_STATUS_DATA::ID => {
32917 WINCH_STATUS_DATA::deser(version, payload).map(Self::WINCH_STATUS)
32918 }
32919 WIND_COV_DATA::ID => WIND_COV_DATA::deser(version, payload).map(Self::WIND_COV),
32920 _ => Err(::mavlink_core::error::ParserError::UnknownMessage { id }),
32921 }
32922 }
32923 fn message_name(&self) -> &'static str {
32924 match self {
32925 Self::ACTUATOR_CONTROL_TARGET(..) => ACTUATOR_CONTROL_TARGET_DATA::NAME,
32926 Self::ACTUATOR_OUTPUT_STATUS(..) => ACTUATOR_OUTPUT_STATUS_DATA::NAME,
32927 Self::ADSB_VEHICLE(..) => ADSB_VEHICLE_DATA::NAME,
32928 Self::AIS_VESSEL(..) => AIS_VESSEL_DATA::NAME,
32929 Self::ALTITUDE(..) => ALTITUDE_DATA::NAME,
32930 Self::ATTITUDE(..) => ATTITUDE_DATA::NAME,
32931 Self::ATTITUDE_QUATERNION(..) => ATTITUDE_QUATERNION_DATA::NAME,
32932 Self::ATTITUDE_QUATERNION_COV(..) => ATTITUDE_QUATERNION_COV_DATA::NAME,
32933 Self::ATTITUDE_TARGET(..) => ATTITUDE_TARGET_DATA::NAME,
32934 Self::ATT_POS_MOCAP(..) => ATT_POS_MOCAP_DATA::NAME,
32935 Self::AUTH_KEY(..) => AUTH_KEY_DATA::NAME,
32936 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(..) => {
32937 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::NAME
32938 }
32939 Self::AUTOPILOT_VERSION(..) => AUTOPILOT_VERSION_DATA::NAME,
32940 Self::AVAILABLE_MODES(..) => AVAILABLE_MODES_DATA::NAME,
32941 Self::AVAILABLE_MODES_MONITOR(..) => AVAILABLE_MODES_MONITOR_DATA::NAME,
32942 Self::BATTERY_INFO(..) => BATTERY_INFO_DATA::NAME,
32943 Self::BATTERY_STATUS(..) => BATTERY_STATUS_DATA::NAME,
32944 Self::BUTTON_CHANGE(..) => BUTTON_CHANGE_DATA::NAME,
32945 Self::CAMERA_CAPTURE_STATUS(..) => CAMERA_CAPTURE_STATUS_DATA::NAME,
32946 Self::CAMERA_FOV_STATUS(..) => CAMERA_FOV_STATUS_DATA::NAME,
32947 Self::CAMERA_IMAGE_CAPTURED(..) => CAMERA_IMAGE_CAPTURED_DATA::NAME,
32948 Self::CAMERA_INFORMATION(..) => CAMERA_INFORMATION_DATA::NAME,
32949 Self::CAMERA_SETTINGS(..) => CAMERA_SETTINGS_DATA::NAME,
32950 Self::CAMERA_THERMAL_RANGE(..) => CAMERA_THERMAL_RANGE_DATA::NAME,
32951 Self::CAMERA_TRACKING_GEO_STATUS(..) => CAMERA_TRACKING_GEO_STATUS_DATA::NAME,
32952 Self::CAMERA_TRACKING_IMAGE_STATUS(..) => CAMERA_TRACKING_IMAGE_STATUS_DATA::NAME,
32953 Self::CAMERA_TRIGGER(..) => CAMERA_TRIGGER_DATA::NAME,
32954 Self::CANFD_FRAME(..) => CANFD_FRAME_DATA::NAME,
32955 Self::CAN_FILTER_MODIFY(..) => CAN_FILTER_MODIFY_DATA::NAME,
32956 Self::CAN_FRAME(..) => CAN_FRAME_DATA::NAME,
32957 Self::CELLULAR_CONFIG(..) => CELLULAR_CONFIG_DATA::NAME,
32958 Self::CELLULAR_STATUS(..) => CELLULAR_STATUS_DATA::NAME,
32959 Self::CHANGE_OPERATOR_CONTROL(..) => CHANGE_OPERATOR_CONTROL_DATA::NAME,
32960 Self::CHANGE_OPERATOR_CONTROL_ACK(..) => CHANGE_OPERATOR_CONTROL_ACK_DATA::NAME,
32961 Self::COLLISION(..) => COLLISION_DATA::NAME,
32962 Self::COMMAND_ACK(..) => COMMAND_ACK_DATA::NAME,
32963 Self::COMMAND_CANCEL(..) => COMMAND_CANCEL_DATA::NAME,
32964 Self::COMMAND_INT(..) => COMMAND_INT_DATA::NAME,
32965 Self::COMMAND_LONG(..) => COMMAND_LONG_DATA::NAME,
32966 Self::COMPONENT_INFORMATION(..) => COMPONENT_INFORMATION_DATA::NAME,
32967 Self::COMPONENT_INFORMATION_BASIC(..) => COMPONENT_INFORMATION_BASIC_DATA::NAME,
32968 Self::COMPONENT_METADATA(..) => COMPONENT_METADATA_DATA::NAME,
32969 Self::CONTROL_SYSTEM_STATE(..) => CONTROL_SYSTEM_STATE_DATA::NAME,
32970 Self::CURRENT_EVENT_SEQUENCE(..) => CURRENT_EVENT_SEQUENCE_DATA::NAME,
32971 Self::CURRENT_MODE(..) => CURRENT_MODE_DATA::NAME,
32972 Self::DATA_STREAM(..) => DATA_STREAM_DATA::NAME,
32973 Self::DATA_TRANSMISSION_HANDSHAKE(..) => DATA_TRANSMISSION_HANDSHAKE_DATA::NAME,
32974 Self::DEBUG(..) => DEBUG_DATA::NAME,
32975 Self::DEBUG_FLOAT_ARRAY(..) => DEBUG_FLOAT_ARRAY_DATA::NAME,
32976 Self::DEBUG_VECT(..) => DEBUG_VECT_DATA::NAME,
32977 Self::DISTANCE_SENSOR(..) => DISTANCE_SENSOR_DATA::NAME,
32978 Self::EFI_STATUS(..) => EFI_STATUS_DATA::NAME,
32979 Self::ENCAPSULATED_DATA(..) => ENCAPSULATED_DATA_DATA::NAME,
32980 Self::ESC_INFO(..) => ESC_INFO_DATA::NAME,
32981 Self::ESC_STATUS(..) => ESC_STATUS_DATA::NAME,
32982 Self::ESTIMATOR_STATUS(..) => ESTIMATOR_STATUS_DATA::NAME,
32983 Self::EVENT(..) => EVENT_DATA::NAME,
32984 Self::EXTENDED_SYS_STATE(..) => EXTENDED_SYS_STATE_DATA::NAME,
32985 Self::FENCE_STATUS(..) => FENCE_STATUS_DATA::NAME,
32986 Self::FILE_TRANSFER_PROTOCOL(..) => FILE_TRANSFER_PROTOCOL_DATA::NAME,
32987 Self::FLIGHT_INFORMATION(..) => FLIGHT_INFORMATION_DATA::NAME,
32988 Self::FOLLOW_TARGET(..) => FOLLOW_TARGET_DATA::NAME,
32989 Self::FUEL_STATUS(..) => FUEL_STATUS_DATA::NAME,
32990 Self::GENERATOR_STATUS(..) => GENERATOR_STATUS_DATA::NAME,
32991 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(..) => GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::NAME,
32992 Self::GIMBAL_DEVICE_INFORMATION(..) => GIMBAL_DEVICE_INFORMATION_DATA::NAME,
32993 Self::GIMBAL_DEVICE_SET_ATTITUDE(..) => GIMBAL_DEVICE_SET_ATTITUDE_DATA::NAME,
32994 Self::GIMBAL_MANAGER_INFORMATION(..) => GIMBAL_MANAGER_INFORMATION_DATA::NAME,
32995 Self::GIMBAL_MANAGER_SET_ATTITUDE(..) => GIMBAL_MANAGER_SET_ATTITUDE_DATA::NAME,
32996 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(..) => {
32997 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::NAME
32998 }
32999 Self::GIMBAL_MANAGER_SET_PITCHYAW(..) => GIMBAL_MANAGER_SET_PITCHYAW_DATA::NAME,
33000 Self::GIMBAL_MANAGER_STATUS(..) => GIMBAL_MANAGER_STATUS_DATA::NAME,
33001 Self::GLOBAL_POSITION_INT(..) => GLOBAL_POSITION_INT_DATA::NAME,
33002 Self::GLOBAL_POSITION_INT_COV(..) => GLOBAL_POSITION_INT_COV_DATA::NAME,
33003 Self::GLOBAL_VISION_POSITION_ESTIMATE(..) => GLOBAL_VISION_POSITION_ESTIMATE_DATA::NAME,
33004 Self::GPS2_RAW(..) => GPS2_RAW_DATA::NAME,
33005 Self::GPS2_RTK(..) => GPS2_RTK_DATA::NAME,
33006 Self::GPS_GLOBAL_ORIGIN(..) => GPS_GLOBAL_ORIGIN_DATA::NAME,
33007 Self::GPS_INJECT_DATA(..) => GPS_INJECT_DATA_DATA::NAME,
33008 Self::GPS_INPUT(..) => GPS_INPUT_DATA::NAME,
33009 Self::GPS_RAW_INT(..) => GPS_RAW_INT_DATA::NAME,
33010 Self::GPS_RTCM_DATA(..) => GPS_RTCM_DATA_DATA::NAME,
33011 Self::GPS_RTK(..) => GPS_RTK_DATA::NAME,
33012 Self::GPS_STATUS(..) => GPS_STATUS_DATA::NAME,
33013 Self::HEARTBEAT(..) => HEARTBEAT_DATA::NAME,
33014 Self::HIGHRES_IMU(..) => HIGHRES_IMU_DATA::NAME,
33015 Self::HIGH_LATENCY(..) => HIGH_LATENCY_DATA::NAME,
33016 Self::HIGH_LATENCY2(..) => HIGH_LATENCY2_DATA::NAME,
33017 Self::HIL_ACTUATOR_CONTROLS(..) => HIL_ACTUATOR_CONTROLS_DATA::NAME,
33018 Self::HIL_CONTROLS(..) => HIL_CONTROLS_DATA::NAME,
33019 Self::HIL_GPS(..) => HIL_GPS_DATA::NAME,
33020 Self::HIL_OPTICAL_FLOW(..) => HIL_OPTICAL_FLOW_DATA::NAME,
33021 Self::HIL_RC_INPUTS_RAW(..) => HIL_RC_INPUTS_RAW_DATA::NAME,
33022 Self::HIL_SENSOR(..) => HIL_SENSOR_DATA::NAME,
33023 Self::HIL_STATE(..) => HIL_STATE_DATA::NAME,
33024 Self::HIL_STATE_QUATERNION(..) => HIL_STATE_QUATERNION_DATA::NAME,
33025 Self::HOME_POSITION(..) => HOME_POSITION_DATA::NAME,
33026 Self::HYGROMETER_SENSOR(..) => HYGROMETER_SENSOR_DATA::NAME,
33027 Self::ILLUMINATOR_STATUS(..) => ILLUMINATOR_STATUS_DATA::NAME,
33028 Self::ISBD_LINK_STATUS(..) => ISBD_LINK_STATUS_DATA::NAME,
33029 Self::LANDING_TARGET(..) => LANDING_TARGET_DATA::NAME,
33030 Self::LINK_NODE_STATUS(..) => LINK_NODE_STATUS_DATA::NAME,
33031 Self::LOCAL_POSITION_NED(..) => LOCAL_POSITION_NED_DATA::NAME,
33032 Self::LOCAL_POSITION_NED_COV(..) => LOCAL_POSITION_NED_COV_DATA::NAME,
33033 Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(..) => {
33034 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::NAME
33035 }
33036 Self::LOGGING_ACK(..) => LOGGING_ACK_DATA::NAME,
33037 Self::LOGGING_DATA(..) => LOGGING_DATA_DATA::NAME,
33038 Self::LOGGING_DATA_ACKED(..) => LOGGING_DATA_ACKED_DATA::NAME,
33039 Self::LOG_DATA(..) => LOG_DATA_DATA::NAME,
33040 Self::LOG_ENTRY(..) => LOG_ENTRY_DATA::NAME,
33041 Self::LOG_ERASE(..) => LOG_ERASE_DATA::NAME,
33042 Self::LOG_REQUEST_DATA(..) => LOG_REQUEST_DATA_DATA::NAME,
33043 Self::LOG_REQUEST_END(..) => LOG_REQUEST_END_DATA::NAME,
33044 Self::LOG_REQUEST_LIST(..) => LOG_REQUEST_LIST_DATA::NAME,
33045 Self::MAG_CAL_REPORT(..) => MAG_CAL_REPORT_DATA::NAME,
33046 Self::MANUAL_CONTROL(..) => MANUAL_CONTROL_DATA::NAME,
33047 Self::MANUAL_SETPOINT(..) => MANUAL_SETPOINT_DATA::NAME,
33048 Self::MEMORY_VECT(..) => MEMORY_VECT_DATA::NAME,
33049 Self::MESSAGE_INTERVAL(..) => MESSAGE_INTERVAL_DATA::NAME,
33050 Self::MISSION_ACK(..) => MISSION_ACK_DATA::NAME,
33051 Self::MISSION_CLEAR_ALL(..) => MISSION_CLEAR_ALL_DATA::NAME,
33052 Self::MISSION_COUNT(..) => MISSION_COUNT_DATA::NAME,
33053 Self::MISSION_CURRENT(..) => MISSION_CURRENT_DATA::NAME,
33054 Self::MISSION_ITEM(..) => MISSION_ITEM_DATA::NAME,
33055 Self::MISSION_ITEM_INT(..) => MISSION_ITEM_INT_DATA::NAME,
33056 Self::MISSION_ITEM_REACHED(..) => MISSION_ITEM_REACHED_DATA::NAME,
33057 Self::MISSION_REQUEST(..) => MISSION_REQUEST_DATA::NAME,
33058 Self::MISSION_REQUEST_INT(..) => MISSION_REQUEST_INT_DATA::NAME,
33059 Self::MISSION_REQUEST_LIST(..) => MISSION_REQUEST_LIST_DATA::NAME,
33060 Self::MISSION_REQUEST_PARTIAL_LIST(..) => MISSION_REQUEST_PARTIAL_LIST_DATA::NAME,
33061 Self::MISSION_SET_CURRENT(..) => MISSION_SET_CURRENT_DATA::NAME,
33062 Self::MISSION_WRITE_PARTIAL_LIST(..) => MISSION_WRITE_PARTIAL_LIST_DATA::NAME,
33063 Self::MOUNT_ORIENTATION(..) => MOUNT_ORIENTATION_DATA::NAME,
33064 Self::NAMED_VALUE_FLOAT(..) => NAMED_VALUE_FLOAT_DATA::NAME,
33065 Self::NAMED_VALUE_INT(..) => NAMED_VALUE_INT_DATA::NAME,
33066 Self::NAV_CONTROLLER_OUTPUT(..) => NAV_CONTROLLER_OUTPUT_DATA::NAME,
33067 Self::OBSTACLE_DISTANCE(..) => OBSTACLE_DISTANCE_DATA::NAME,
33068 Self::ODOMETRY(..) => ODOMETRY_DATA::NAME,
33069 Self::ONBOARD_COMPUTER_STATUS(..) => ONBOARD_COMPUTER_STATUS_DATA::NAME,
33070 Self::OPEN_DRONE_ID_ARM_STATUS(..) => OPEN_DRONE_ID_ARM_STATUS_DATA::NAME,
33071 Self::OPEN_DRONE_ID_AUTHENTICATION(..) => OPEN_DRONE_ID_AUTHENTICATION_DATA::NAME,
33072 Self::OPEN_DRONE_ID_BASIC_ID(..) => OPEN_DRONE_ID_BASIC_ID_DATA::NAME,
33073 Self::OPEN_DRONE_ID_LOCATION(..) => OPEN_DRONE_ID_LOCATION_DATA::NAME,
33074 Self::OPEN_DRONE_ID_MESSAGE_PACK(..) => OPEN_DRONE_ID_MESSAGE_PACK_DATA::NAME,
33075 Self::OPEN_DRONE_ID_OPERATOR_ID(..) => OPEN_DRONE_ID_OPERATOR_ID_DATA::NAME,
33076 Self::OPEN_DRONE_ID_SELF_ID(..) => OPEN_DRONE_ID_SELF_ID_DATA::NAME,
33077 Self::OPEN_DRONE_ID_SYSTEM(..) => OPEN_DRONE_ID_SYSTEM_DATA::NAME,
33078 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(..) => OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::NAME,
33079 Self::OPTICAL_FLOW(..) => OPTICAL_FLOW_DATA::NAME,
33080 Self::OPTICAL_FLOW_RAD(..) => OPTICAL_FLOW_RAD_DATA::NAME,
33081 Self::ORBIT_EXECUTION_STATUS(..) => ORBIT_EXECUTION_STATUS_DATA::NAME,
33082 Self::PARAM_EXT_ACK(..) => PARAM_EXT_ACK_DATA::NAME,
33083 Self::PARAM_EXT_REQUEST_LIST(..) => PARAM_EXT_REQUEST_LIST_DATA::NAME,
33084 Self::PARAM_EXT_REQUEST_READ(..) => PARAM_EXT_REQUEST_READ_DATA::NAME,
33085 Self::PARAM_EXT_SET(..) => PARAM_EXT_SET_DATA::NAME,
33086 Self::PARAM_EXT_VALUE(..) => PARAM_EXT_VALUE_DATA::NAME,
33087 Self::PARAM_MAP_RC(..) => PARAM_MAP_RC_DATA::NAME,
33088 Self::PARAM_REQUEST_LIST(..) => PARAM_REQUEST_LIST_DATA::NAME,
33089 Self::PARAM_REQUEST_READ(..) => PARAM_REQUEST_READ_DATA::NAME,
33090 Self::PARAM_SET(..) => PARAM_SET_DATA::NAME,
33091 Self::PARAM_VALUE(..) => PARAM_VALUE_DATA::NAME,
33092 Self::PING(..) => PING_DATA::NAME,
33093 Self::PLAY_TUNE(..) => PLAY_TUNE_DATA::NAME,
33094 Self::PLAY_TUNE_V2(..) => PLAY_TUNE_V2_DATA::NAME,
33095 Self::POSITION_TARGET_GLOBAL_INT(..) => POSITION_TARGET_GLOBAL_INT_DATA::NAME,
33096 Self::POSITION_TARGET_LOCAL_NED(..) => POSITION_TARGET_LOCAL_NED_DATA::NAME,
33097 Self::POWER_STATUS(..) => POWER_STATUS_DATA::NAME,
33098 Self::PROTOCOL_VERSION(..) => PROTOCOL_VERSION_DATA::NAME,
33099 Self::RADIO_STATUS(..) => RADIO_STATUS_DATA::NAME,
33100 Self::RAW_IMU(..) => RAW_IMU_DATA::NAME,
33101 Self::RAW_PRESSURE(..) => RAW_PRESSURE_DATA::NAME,
33102 Self::RAW_RPM(..) => RAW_RPM_DATA::NAME,
33103 Self::RC_CHANNELS(..) => RC_CHANNELS_DATA::NAME,
33104 Self::RC_CHANNELS_OVERRIDE(..) => RC_CHANNELS_OVERRIDE_DATA::NAME,
33105 Self::RC_CHANNELS_RAW(..) => RC_CHANNELS_RAW_DATA::NAME,
33106 Self::RC_CHANNELS_SCALED(..) => RC_CHANNELS_SCALED_DATA::NAME,
33107 Self::REQUEST_DATA_STREAM(..) => REQUEST_DATA_STREAM_DATA::NAME,
33108 Self::REQUEST_EVENT(..) => REQUEST_EVENT_DATA::NAME,
33109 Self::RESOURCE_REQUEST(..) => RESOURCE_REQUEST_DATA::NAME,
33110 Self::RESPONSE_EVENT_ERROR(..) => RESPONSE_EVENT_ERROR_DATA::NAME,
33111 Self::SAFETY_ALLOWED_AREA(..) => SAFETY_ALLOWED_AREA_DATA::NAME,
33112 Self::SAFETY_SET_ALLOWED_AREA(..) => SAFETY_SET_ALLOWED_AREA_DATA::NAME,
33113 Self::SCALED_IMU(..) => SCALED_IMU_DATA::NAME,
33114 Self::SCALED_IMU2(..) => SCALED_IMU2_DATA::NAME,
33115 Self::SCALED_IMU3(..) => SCALED_IMU3_DATA::NAME,
33116 Self::SCALED_PRESSURE(..) => SCALED_PRESSURE_DATA::NAME,
33117 Self::SCALED_PRESSURE2(..) => SCALED_PRESSURE2_DATA::NAME,
33118 Self::SCALED_PRESSURE3(..) => SCALED_PRESSURE3_DATA::NAME,
33119 Self::SERIAL_CONTROL(..) => SERIAL_CONTROL_DATA::NAME,
33120 Self::SERVO_OUTPUT_RAW(..) => SERVO_OUTPUT_RAW_DATA::NAME,
33121 Self::SETUP_SIGNING(..) => SETUP_SIGNING_DATA::NAME,
33122 Self::SET_ACTUATOR_CONTROL_TARGET(..) => SET_ACTUATOR_CONTROL_TARGET_DATA::NAME,
33123 Self::SET_ATTITUDE_TARGET(..) => SET_ATTITUDE_TARGET_DATA::NAME,
33124 Self::SET_GPS_GLOBAL_ORIGIN(..) => SET_GPS_GLOBAL_ORIGIN_DATA::NAME,
33125 Self::SET_HOME_POSITION(..) => SET_HOME_POSITION_DATA::NAME,
33126 Self::SET_MODE(..) => SET_MODE_DATA::NAME,
33127 Self::SET_POSITION_TARGET_GLOBAL_INT(..) => SET_POSITION_TARGET_GLOBAL_INT_DATA::NAME,
33128 Self::SET_POSITION_TARGET_LOCAL_NED(..) => SET_POSITION_TARGET_LOCAL_NED_DATA::NAME,
33129 Self::SIM_STATE(..) => SIM_STATE_DATA::NAME,
33130 Self::SMART_BATTERY_INFO(..) => SMART_BATTERY_INFO_DATA::NAME,
33131 Self::STATUSTEXT(..) => STATUSTEXT_DATA::NAME,
33132 Self::STORAGE_INFORMATION(..) => STORAGE_INFORMATION_DATA::NAME,
33133 Self::SUPPORTED_TUNES(..) => SUPPORTED_TUNES_DATA::NAME,
33134 Self::SYSTEM_TIME(..) => SYSTEM_TIME_DATA::NAME,
33135 Self::SYS_STATUS(..) => SYS_STATUS_DATA::NAME,
33136 Self::TERRAIN_CHECK(..) => TERRAIN_CHECK_DATA::NAME,
33137 Self::TERRAIN_DATA(..) => TERRAIN_DATA_DATA::NAME,
33138 Self::TERRAIN_REPORT(..) => TERRAIN_REPORT_DATA::NAME,
33139 Self::TERRAIN_REQUEST(..) => TERRAIN_REQUEST_DATA::NAME,
33140 Self::TIMESYNC(..) => TIMESYNC_DATA::NAME,
33141 Self::TIME_ESTIMATE_TO_TARGET(..) => TIME_ESTIMATE_TO_TARGET_DATA::NAME,
33142 Self::TRAJECTORY_REPRESENTATION_BEZIER(..) => {
33143 TRAJECTORY_REPRESENTATION_BEZIER_DATA::NAME
33144 }
33145 Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(..) => {
33146 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::NAME
33147 }
33148 Self::TUNNEL(..) => TUNNEL_DATA::NAME,
33149 Self::UAVCAN_NODE_INFO(..) => UAVCAN_NODE_INFO_DATA::NAME,
33150 Self::UAVCAN_NODE_STATUS(..) => UAVCAN_NODE_STATUS_DATA::NAME,
33151 Self::UAVIONIX_ADSB_GET(..) => UAVIONIX_ADSB_GET_DATA::NAME,
33152 Self::UAVIONIX_ADSB_OUT_CFG(..) => UAVIONIX_ADSB_OUT_CFG_DATA::NAME,
33153 Self::UAVIONIX_ADSB_OUT_CFG_FLIGHTID(..) => UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::NAME,
33154 Self::UAVIONIX_ADSB_OUT_CFG_REGISTRATION(..) => {
33155 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::NAME
33156 }
33157 Self::UAVIONIX_ADSB_OUT_CONTROL(..) => UAVIONIX_ADSB_OUT_CONTROL_DATA::NAME,
33158 Self::UAVIONIX_ADSB_OUT_DYNAMIC(..) => UAVIONIX_ADSB_OUT_DYNAMIC_DATA::NAME,
33159 Self::UAVIONIX_ADSB_OUT_STATUS(..) => UAVIONIX_ADSB_OUT_STATUS_DATA::NAME,
33160 Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(..) => {
33161 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::NAME
33162 }
33163 Self::UTM_GLOBAL_POSITION(..) => UTM_GLOBAL_POSITION_DATA::NAME,
33164 Self::V2_EXTENSION(..) => V2_EXTENSION_DATA::NAME,
33165 Self::VFR_HUD(..) => VFR_HUD_DATA::NAME,
33166 Self::VIBRATION(..) => VIBRATION_DATA::NAME,
33167 Self::VICON_POSITION_ESTIMATE(..) => VICON_POSITION_ESTIMATE_DATA::NAME,
33168 Self::VIDEO_STREAM_INFORMATION(..) => VIDEO_STREAM_INFORMATION_DATA::NAME,
33169 Self::VIDEO_STREAM_STATUS(..) => VIDEO_STREAM_STATUS_DATA::NAME,
33170 Self::VISION_POSITION_ESTIMATE(..) => VISION_POSITION_ESTIMATE_DATA::NAME,
33171 Self::VISION_SPEED_ESTIMATE(..) => VISION_SPEED_ESTIMATE_DATA::NAME,
33172 Self::WHEEL_DISTANCE(..) => WHEEL_DISTANCE_DATA::NAME,
33173 Self::WIFI_CONFIG_AP(..) => WIFI_CONFIG_AP_DATA::NAME,
33174 Self::WINCH_STATUS(..) => WINCH_STATUS_DATA::NAME,
33175 Self::WIND_COV(..) => WIND_COV_DATA::NAME,
33176 }
33177 }
33178 fn message_id(&self) -> u32 {
33179 match self {
33180 Self::ACTUATOR_CONTROL_TARGET(..) => ACTUATOR_CONTROL_TARGET_DATA::ID,
33181 Self::ACTUATOR_OUTPUT_STATUS(..) => ACTUATOR_OUTPUT_STATUS_DATA::ID,
33182 Self::ADSB_VEHICLE(..) => ADSB_VEHICLE_DATA::ID,
33183 Self::AIS_VESSEL(..) => AIS_VESSEL_DATA::ID,
33184 Self::ALTITUDE(..) => ALTITUDE_DATA::ID,
33185 Self::ATTITUDE(..) => ATTITUDE_DATA::ID,
33186 Self::ATTITUDE_QUATERNION(..) => ATTITUDE_QUATERNION_DATA::ID,
33187 Self::ATTITUDE_QUATERNION_COV(..) => ATTITUDE_QUATERNION_COV_DATA::ID,
33188 Self::ATTITUDE_TARGET(..) => ATTITUDE_TARGET_DATA::ID,
33189 Self::ATT_POS_MOCAP(..) => ATT_POS_MOCAP_DATA::ID,
33190 Self::AUTH_KEY(..) => AUTH_KEY_DATA::ID,
33191 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(..) => {
33192 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID
33193 }
33194 Self::AUTOPILOT_VERSION(..) => AUTOPILOT_VERSION_DATA::ID,
33195 Self::AVAILABLE_MODES(..) => AVAILABLE_MODES_DATA::ID,
33196 Self::AVAILABLE_MODES_MONITOR(..) => AVAILABLE_MODES_MONITOR_DATA::ID,
33197 Self::BATTERY_INFO(..) => BATTERY_INFO_DATA::ID,
33198 Self::BATTERY_STATUS(..) => BATTERY_STATUS_DATA::ID,
33199 Self::BUTTON_CHANGE(..) => BUTTON_CHANGE_DATA::ID,
33200 Self::CAMERA_CAPTURE_STATUS(..) => CAMERA_CAPTURE_STATUS_DATA::ID,
33201 Self::CAMERA_FOV_STATUS(..) => CAMERA_FOV_STATUS_DATA::ID,
33202 Self::CAMERA_IMAGE_CAPTURED(..) => CAMERA_IMAGE_CAPTURED_DATA::ID,
33203 Self::CAMERA_INFORMATION(..) => CAMERA_INFORMATION_DATA::ID,
33204 Self::CAMERA_SETTINGS(..) => CAMERA_SETTINGS_DATA::ID,
33205 Self::CAMERA_THERMAL_RANGE(..) => CAMERA_THERMAL_RANGE_DATA::ID,
33206 Self::CAMERA_TRACKING_GEO_STATUS(..) => CAMERA_TRACKING_GEO_STATUS_DATA::ID,
33207 Self::CAMERA_TRACKING_IMAGE_STATUS(..) => CAMERA_TRACKING_IMAGE_STATUS_DATA::ID,
33208 Self::CAMERA_TRIGGER(..) => CAMERA_TRIGGER_DATA::ID,
33209 Self::CANFD_FRAME(..) => CANFD_FRAME_DATA::ID,
33210 Self::CAN_FILTER_MODIFY(..) => CAN_FILTER_MODIFY_DATA::ID,
33211 Self::CAN_FRAME(..) => CAN_FRAME_DATA::ID,
33212 Self::CELLULAR_CONFIG(..) => CELLULAR_CONFIG_DATA::ID,
33213 Self::CELLULAR_STATUS(..) => CELLULAR_STATUS_DATA::ID,
33214 Self::CHANGE_OPERATOR_CONTROL(..) => CHANGE_OPERATOR_CONTROL_DATA::ID,
33215 Self::CHANGE_OPERATOR_CONTROL_ACK(..) => CHANGE_OPERATOR_CONTROL_ACK_DATA::ID,
33216 Self::COLLISION(..) => COLLISION_DATA::ID,
33217 Self::COMMAND_ACK(..) => COMMAND_ACK_DATA::ID,
33218 Self::COMMAND_CANCEL(..) => COMMAND_CANCEL_DATA::ID,
33219 Self::COMMAND_INT(..) => COMMAND_INT_DATA::ID,
33220 Self::COMMAND_LONG(..) => COMMAND_LONG_DATA::ID,
33221 Self::COMPONENT_INFORMATION(..) => COMPONENT_INFORMATION_DATA::ID,
33222 Self::COMPONENT_INFORMATION_BASIC(..) => COMPONENT_INFORMATION_BASIC_DATA::ID,
33223 Self::COMPONENT_METADATA(..) => COMPONENT_METADATA_DATA::ID,
33224 Self::CONTROL_SYSTEM_STATE(..) => CONTROL_SYSTEM_STATE_DATA::ID,
33225 Self::CURRENT_EVENT_SEQUENCE(..) => CURRENT_EVENT_SEQUENCE_DATA::ID,
33226 Self::CURRENT_MODE(..) => CURRENT_MODE_DATA::ID,
33227 Self::DATA_STREAM(..) => DATA_STREAM_DATA::ID,
33228 Self::DATA_TRANSMISSION_HANDSHAKE(..) => DATA_TRANSMISSION_HANDSHAKE_DATA::ID,
33229 Self::DEBUG(..) => DEBUG_DATA::ID,
33230 Self::DEBUG_FLOAT_ARRAY(..) => DEBUG_FLOAT_ARRAY_DATA::ID,
33231 Self::DEBUG_VECT(..) => DEBUG_VECT_DATA::ID,
33232 Self::DISTANCE_SENSOR(..) => DISTANCE_SENSOR_DATA::ID,
33233 Self::EFI_STATUS(..) => EFI_STATUS_DATA::ID,
33234 Self::ENCAPSULATED_DATA(..) => ENCAPSULATED_DATA_DATA::ID,
33235 Self::ESC_INFO(..) => ESC_INFO_DATA::ID,
33236 Self::ESC_STATUS(..) => ESC_STATUS_DATA::ID,
33237 Self::ESTIMATOR_STATUS(..) => ESTIMATOR_STATUS_DATA::ID,
33238 Self::EVENT(..) => EVENT_DATA::ID,
33239 Self::EXTENDED_SYS_STATE(..) => EXTENDED_SYS_STATE_DATA::ID,
33240 Self::FENCE_STATUS(..) => FENCE_STATUS_DATA::ID,
33241 Self::FILE_TRANSFER_PROTOCOL(..) => FILE_TRANSFER_PROTOCOL_DATA::ID,
33242 Self::FLIGHT_INFORMATION(..) => FLIGHT_INFORMATION_DATA::ID,
33243 Self::FOLLOW_TARGET(..) => FOLLOW_TARGET_DATA::ID,
33244 Self::FUEL_STATUS(..) => FUEL_STATUS_DATA::ID,
33245 Self::GENERATOR_STATUS(..) => GENERATOR_STATUS_DATA::ID,
33246 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(..) => GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID,
33247 Self::GIMBAL_DEVICE_INFORMATION(..) => GIMBAL_DEVICE_INFORMATION_DATA::ID,
33248 Self::GIMBAL_DEVICE_SET_ATTITUDE(..) => GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID,
33249 Self::GIMBAL_MANAGER_INFORMATION(..) => GIMBAL_MANAGER_INFORMATION_DATA::ID,
33250 Self::GIMBAL_MANAGER_SET_ATTITUDE(..) => GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID,
33251 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(..) => {
33252 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID
33253 }
33254 Self::GIMBAL_MANAGER_SET_PITCHYAW(..) => GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID,
33255 Self::GIMBAL_MANAGER_STATUS(..) => GIMBAL_MANAGER_STATUS_DATA::ID,
33256 Self::GLOBAL_POSITION_INT(..) => GLOBAL_POSITION_INT_DATA::ID,
33257 Self::GLOBAL_POSITION_INT_COV(..) => GLOBAL_POSITION_INT_COV_DATA::ID,
33258 Self::GLOBAL_VISION_POSITION_ESTIMATE(..) => GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID,
33259 Self::GPS2_RAW(..) => GPS2_RAW_DATA::ID,
33260 Self::GPS2_RTK(..) => GPS2_RTK_DATA::ID,
33261 Self::GPS_GLOBAL_ORIGIN(..) => GPS_GLOBAL_ORIGIN_DATA::ID,
33262 Self::GPS_INJECT_DATA(..) => GPS_INJECT_DATA_DATA::ID,
33263 Self::GPS_INPUT(..) => GPS_INPUT_DATA::ID,
33264 Self::GPS_RAW_INT(..) => GPS_RAW_INT_DATA::ID,
33265 Self::GPS_RTCM_DATA(..) => GPS_RTCM_DATA_DATA::ID,
33266 Self::GPS_RTK(..) => GPS_RTK_DATA::ID,
33267 Self::GPS_STATUS(..) => GPS_STATUS_DATA::ID,
33268 Self::HEARTBEAT(..) => HEARTBEAT_DATA::ID,
33269 Self::HIGHRES_IMU(..) => HIGHRES_IMU_DATA::ID,
33270 Self::HIGH_LATENCY(..) => HIGH_LATENCY_DATA::ID,
33271 Self::HIGH_LATENCY2(..) => HIGH_LATENCY2_DATA::ID,
33272 Self::HIL_ACTUATOR_CONTROLS(..) => HIL_ACTUATOR_CONTROLS_DATA::ID,
33273 Self::HIL_CONTROLS(..) => HIL_CONTROLS_DATA::ID,
33274 Self::HIL_GPS(..) => HIL_GPS_DATA::ID,
33275 Self::HIL_OPTICAL_FLOW(..) => HIL_OPTICAL_FLOW_DATA::ID,
33276 Self::HIL_RC_INPUTS_RAW(..) => HIL_RC_INPUTS_RAW_DATA::ID,
33277 Self::HIL_SENSOR(..) => HIL_SENSOR_DATA::ID,
33278 Self::HIL_STATE(..) => HIL_STATE_DATA::ID,
33279 Self::HIL_STATE_QUATERNION(..) => HIL_STATE_QUATERNION_DATA::ID,
33280 Self::HOME_POSITION(..) => HOME_POSITION_DATA::ID,
33281 Self::HYGROMETER_SENSOR(..) => HYGROMETER_SENSOR_DATA::ID,
33282 Self::ILLUMINATOR_STATUS(..) => ILLUMINATOR_STATUS_DATA::ID,
33283 Self::ISBD_LINK_STATUS(..) => ISBD_LINK_STATUS_DATA::ID,
33284 Self::LANDING_TARGET(..) => LANDING_TARGET_DATA::ID,
33285 Self::LINK_NODE_STATUS(..) => LINK_NODE_STATUS_DATA::ID,
33286 Self::LOCAL_POSITION_NED(..) => LOCAL_POSITION_NED_DATA::ID,
33287 Self::LOCAL_POSITION_NED_COV(..) => LOCAL_POSITION_NED_COV_DATA::ID,
33288 Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(..) => {
33289 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID
33290 }
33291 Self::LOGGING_ACK(..) => LOGGING_ACK_DATA::ID,
33292 Self::LOGGING_DATA(..) => LOGGING_DATA_DATA::ID,
33293 Self::LOGGING_DATA_ACKED(..) => LOGGING_DATA_ACKED_DATA::ID,
33294 Self::LOG_DATA(..) => LOG_DATA_DATA::ID,
33295 Self::LOG_ENTRY(..) => LOG_ENTRY_DATA::ID,
33296 Self::LOG_ERASE(..) => LOG_ERASE_DATA::ID,
33297 Self::LOG_REQUEST_DATA(..) => LOG_REQUEST_DATA_DATA::ID,
33298 Self::LOG_REQUEST_END(..) => LOG_REQUEST_END_DATA::ID,
33299 Self::LOG_REQUEST_LIST(..) => LOG_REQUEST_LIST_DATA::ID,
33300 Self::MAG_CAL_REPORT(..) => MAG_CAL_REPORT_DATA::ID,
33301 Self::MANUAL_CONTROL(..) => MANUAL_CONTROL_DATA::ID,
33302 Self::MANUAL_SETPOINT(..) => MANUAL_SETPOINT_DATA::ID,
33303 Self::MEMORY_VECT(..) => MEMORY_VECT_DATA::ID,
33304 Self::MESSAGE_INTERVAL(..) => MESSAGE_INTERVAL_DATA::ID,
33305 Self::MISSION_ACK(..) => MISSION_ACK_DATA::ID,
33306 Self::MISSION_CLEAR_ALL(..) => MISSION_CLEAR_ALL_DATA::ID,
33307 Self::MISSION_COUNT(..) => MISSION_COUNT_DATA::ID,
33308 Self::MISSION_CURRENT(..) => MISSION_CURRENT_DATA::ID,
33309 Self::MISSION_ITEM(..) => MISSION_ITEM_DATA::ID,
33310 Self::MISSION_ITEM_INT(..) => MISSION_ITEM_INT_DATA::ID,
33311 Self::MISSION_ITEM_REACHED(..) => MISSION_ITEM_REACHED_DATA::ID,
33312 Self::MISSION_REQUEST(..) => MISSION_REQUEST_DATA::ID,
33313 Self::MISSION_REQUEST_INT(..) => MISSION_REQUEST_INT_DATA::ID,
33314 Self::MISSION_REQUEST_LIST(..) => MISSION_REQUEST_LIST_DATA::ID,
33315 Self::MISSION_REQUEST_PARTIAL_LIST(..) => MISSION_REQUEST_PARTIAL_LIST_DATA::ID,
33316 Self::MISSION_SET_CURRENT(..) => MISSION_SET_CURRENT_DATA::ID,
33317 Self::MISSION_WRITE_PARTIAL_LIST(..) => MISSION_WRITE_PARTIAL_LIST_DATA::ID,
33318 Self::MOUNT_ORIENTATION(..) => MOUNT_ORIENTATION_DATA::ID,
33319 Self::NAMED_VALUE_FLOAT(..) => NAMED_VALUE_FLOAT_DATA::ID,
33320 Self::NAMED_VALUE_INT(..) => NAMED_VALUE_INT_DATA::ID,
33321 Self::NAV_CONTROLLER_OUTPUT(..) => NAV_CONTROLLER_OUTPUT_DATA::ID,
33322 Self::OBSTACLE_DISTANCE(..) => OBSTACLE_DISTANCE_DATA::ID,
33323 Self::ODOMETRY(..) => ODOMETRY_DATA::ID,
33324 Self::ONBOARD_COMPUTER_STATUS(..) => ONBOARD_COMPUTER_STATUS_DATA::ID,
33325 Self::OPEN_DRONE_ID_ARM_STATUS(..) => OPEN_DRONE_ID_ARM_STATUS_DATA::ID,
33326 Self::OPEN_DRONE_ID_AUTHENTICATION(..) => OPEN_DRONE_ID_AUTHENTICATION_DATA::ID,
33327 Self::OPEN_DRONE_ID_BASIC_ID(..) => OPEN_DRONE_ID_BASIC_ID_DATA::ID,
33328 Self::OPEN_DRONE_ID_LOCATION(..) => OPEN_DRONE_ID_LOCATION_DATA::ID,
33329 Self::OPEN_DRONE_ID_MESSAGE_PACK(..) => OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID,
33330 Self::OPEN_DRONE_ID_OPERATOR_ID(..) => OPEN_DRONE_ID_OPERATOR_ID_DATA::ID,
33331 Self::OPEN_DRONE_ID_SELF_ID(..) => OPEN_DRONE_ID_SELF_ID_DATA::ID,
33332 Self::OPEN_DRONE_ID_SYSTEM(..) => OPEN_DRONE_ID_SYSTEM_DATA::ID,
33333 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(..) => OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID,
33334 Self::OPTICAL_FLOW(..) => OPTICAL_FLOW_DATA::ID,
33335 Self::OPTICAL_FLOW_RAD(..) => OPTICAL_FLOW_RAD_DATA::ID,
33336 Self::ORBIT_EXECUTION_STATUS(..) => ORBIT_EXECUTION_STATUS_DATA::ID,
33337 Self::PARAM_EXT_ACK(..) => PARAM_EXT_ACK_DATA::ID,
33338 Self::PARAM_EXT_REQUEST_LIST(..) => PARAM_EXT_REQUEST_LIST_DATA::ID,
33339 Self::PARAM_EXT_REQUEST_READ(..) => PARAM_EXT_REQUEST_READ_DATA::ID,
33340 Self::PARAM_EXT_SET(..) => PARAM_EXT_SET_DATA::ID,
33341 Self::PARAM_EXT_VALUE(..) => PARAM_EXT_VALUE_DATA::ID,
33342 Self::PARAM_MAP_RC(..) => PARAM_MAP_RC_DATA::ID,
33343 Self::PARAM_REQUEST_LIST(..) => PARAM_REQUEST_LIST_DATA::ID,
33344 Self::PARAM_REQUEST_READ(..) => PARAM_REQUEST_READ_DATA::ID,
33345 Self::PARAM_SET(..) => PARAM_SET_DATA::ID,
33346 Self::PARAM_VALUE(..) => PARAM_VALUE_DATA::ID,
33347 Self::PING(..) => PING_DATA::ID,
33348 Self::PLAY_TUNE(..) => PLAY_TUNE_DATA::ID,
33349 Self::PLAY_TUNE_V2(..) => PLAY_TUNE_V2_DATA::ID,
33350 Self::POSITION_TARGET_GLOBAL_INT(..) => POSITION_TARGET_GLOBAL_INT_DATA::ID,
33351 Self::POSITION_TARGET_LOCAL_NED(..) => POSITION_TARGET_LOCAL_NED_DATA::ID,
33352 Self::POWER_STATUS(..) => POWER_STATUS_DATA::ID,
33353 Self::PROTOCOL_VERSION(..) => PROTOCOL_VERSION_DATA::ID,
33354 Self::RADIO_STATUS(..) => RADIO_STATUS_DATA::ID,
33355 Self::RAW_IMU(..) => RAW_IMU_DATA::ID,
33356 Self::RAW_PRESSURE(..) => RAW_PRESSURE_DATA::ID,
33357 Self::RAW_RPM(..) => RAW_RPM_DATA::ID,
33358 Self::RC_CHANNELS(..) => RC_CHANNELS_DATA::ID,
33359 Self::RC_CHANNELS_OVERRIDE(..) => RC_CHANNELS_OVERRIDE_DATA::ID,
33360 Self::RC_CHANNELS_RAW(..) => RC_CHANNELS_RAW_DATA::ID,
33361 Self::RC_CHANNELS_SCALED(..) => RC_CHANNELS_SCALED_DATA::ID,
33362 Self::REQUEST_DATA_STREAM(..) => REQUEST_DATA_STREAM_DATA::ID,
33363 Self::REQUEST_EVENT(..) => REQUEST_EVENT_DATA::ID,
33364 Self::RESOURCE_REQUEST(..) => RESOURCE_REQUEST_DATA::ID,
33365 Self::RESPONSE_EVENT_ERROR(..) => RESPONSE_EVENT_ERROR_DATA::ID,
33366 Self::SAFETY_ALLOWED_AREA(..) => SAFETY_ALLOWED_AREA_DATA::ID,
33367 Self::SAFETY_SET_ALLOWED_AREA(..) => SAFETY_SET_ALLOWED_AREA_DATA::ID,
33368 Self::SCALED_IMU(..) => SCALED_IMU_DATA::ID,
33369 Self::SCALED_IMU2(..) => SCALED_IMU2_DATA::ID,
33370 Self::SCALED_IMU3(..) => SCALED_IMU3_DATA::ID,
33371 Self::SCALED_PRESSURE(..) => SCALED_PRESSURE_DATA::ID,
33372 Self::SCALED_PRESSURE2(..) => SCALED_PRESSURE2_DATA::ID,
33373 Self::SCALED_PRESSURE3(..) => SCALED_PRESSURE3_DATA::ID,
33374 Self::SERIAL_CONTROL(..) => SERIAL_CONTROL_DATA::ID,
33375 Self::SERVO_OUTPUT_RAW(..) => SERVO_OUTPUT_RAW_DATA::ID,
33376 Self::SETUP_SIGNING(..) => SETUP_SIGNING_DATA::ID,
33377 Self::SET_ACTUATOR_CONTROL_TARGET(..) => SET_ACTUATOR_CONTROL_TARGET_DATA::ID,
33378 Self::SET_ATTITUDE_TARGET(..) => SET_ATTITUDE_TARGET_DATA::ID,
33379 Self::SET_GPS_GLOBAL_ORIGIN(..) => SET_GPS_GLOBAL_ORIGIN_DATA::ID,
33380 Self::SET_HOME_POSITION(..) => SET_HOME_POSITION_DATA::ID,
33381 Self::SET_MODE(..) => SET_MODE_DATA::ID,
33382 Self::SET_POSITION_TARGET_GLOBAL_INT(..) => SET_POSITION_TARGET_GLOBAL_INT_DATA::ID,
33383 Self::SET_POSITION_TARGET_LOCAL_NED(..) => SET_POSITION_TARGET_LOCAL_NED_DATA::ID,
33384 Self::SIM_STATE(..) => SIM_STATE_DATA::ID,
33385 Self::SMART_BATTERY_INFO(..) => SMART_BATTERY_INFO_DATA::ID,
33386 Self::STATUSTEXT(..) => STATUSTEXT_DATA::ID,
33387 Self::STORAGE_INFORMATION(..) => STORAGE_INFORMATION_DATA::ID,
33388 Self::SUPPORTED_TUNES(..) => SUPPORTED_TUNES_DATA::ID,
33389 Self::SYSTEM_TIME(..) => SYSTEM_TIME_DATA::ID,
33390 Self::SYS_STATUS(..) => SYS_STATUS_DATA::ID,
33391 Self::TERRAIN_CHECK(..) => TERRAIN_CHECK_DATA::ID,
33392 Self::TERRAIN_DATA(..) => TERRAIN_DATA_DATA::ID,
33393 Self::TERRAIN_REPORT(..) => TERRAIN_REPORT_DATA::ID,
33394 Self::TERRAIN_REQUEST(..) => TERRAIN_REQUEST_DATA::ID,
33395 Self::TIMESYNC(..) => TIMESYNC_DATA::ID,
33396 Self::TIME_ESTIMATE_TO_TARGET(..) => TIME_ESTIMATE_TO_TARGET_DATA::ID,
33397 Self::TRAJECTORY_REPRESENTATION_BEZIER(..) => TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID,
33398 Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(..) => {
33399 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID
33400 }
33401 Self::TUNNEL(..) => TUNNEL_DATA::ID,
33402 Self::UAVCAN_NODE_INFO(..) => UAVCAN_NODE_INFO_DATA::ID,
33403 Self::UAVCAN_NODE_STATUS(..) => UAVCAN_NODE_STATUS_DATA::ID,
33404 Self::UAVIONIX_ADSB_GET(..) => UAVIONIX_ADSB_GET_DATA::ID,
33405 Self::UAVIONIX_ADSB_OUT_CFG(..) => UAVIONIX_ADSB_OUT_CFG_DATA::ID,
33406 Self::UAVIONIX_ADSB_OUT_CFG_FLIGHTID(..) => UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::ID,
33407 Self::UAVIONIX_ADSB_OUT_CFG_REGISTRATION(..) => {
33408 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::ID
33409 }
33410 Self::UAVIONIX_ADSB_OUT_CONTROL(..) => UAVIONIX_ADSB_OUT_CONTROL_DATA::ID,
33411 Self::UAVIONIX_ADSB_OUT_DYNAMIC(..) => UAVIONIX_ADSB_OUT_DYNAMIC_DATA::ID,
33412 Self::UAVIONIX_ADSB_OUT_STATUS(..) => UAVIONIX_ADSB_OUT_STATUS_DATA::ID,
33413 Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(..) => {
33414 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::ID
33415 }
33416 Self::UTM_GLOBAL_POSITION(..) => UTM_GLOBAL_POSITION_DATA::ID,
33417 Self::V2_EXTENSION(..) => V2_EXTENSION_DATA::ID,
33418 Self::VFR_HUD(..) => VFR_HUD_DATA::ID,
33419 Self::VIBRATION(..) => VIBRATION_DATA::ID,
33420 Self::VICON_POSITION_ESTIMATE(..) => VICON_POSITION_ESTIMATE_DATA::ID,
33421 Self::VIDEO_STREAM_INFORMATION(..) => VIDEO_STREAM_INFORMATION_DATA::ID,
33422 Self::VIDEO_STREAM_STATUS(..) => VIDEO_STREAM_STATUS_DATA::ID,
33423 Self::VISION_POSITION_ESTIMATE(..) => VISION_POSITION_ESTIMATE_DATA::ID,
33424 Self::VISION_SPEED_ESTIMATE(..) => VISION_SPEED_ESTIMATE_DATA::ID,
33425 Self::WHEEL_DISTANCE(..) => WHEEL_DISTANCE_DATA::ID,
33426 Self::WIFI_CONFIG_AP(..) => WIFI_CONFIG_AP_DATA::ID,
33427 Self::WINCH_STATUS(..) => WINCH_STATUS_DATA::ID,
33428 Self::WIND_COV(..) => WIND_COV_DATA::ID,
33429 }
33430 }
33431 fn message_id_from_name(name: &str) -> Option<u32> {
33432 match name {
33433 ACTUATOR_CONTROL_TARGET_DATA::NAME => Some(ACTUATOR_CONTROL_TARGET_DATA::ID),
33434 ACTUATOR_OUTPUT_STATUS_DATA::NAME => Some(ACTUATOR_OUTPUT_STATUS_DATA::ID),
33435 ADSB_VEHICLE_DATA::NAME => Some(ADSB_VEHICLE_DATA::ID),
33436 AIS_VESSEL_DATA::NAME => Some(AIS_VESSEL_DATA::ID),
33437 ALTITUDE_DATA::NAME => Some(ALTITUDE_DATA::ID),
33438 ATTITUDE_DATA::NAME => Some(ATTITUDE_DATA::ID),
33439 ATTITUDE_QUATERNION_DATA::NAME => Some(ATTITUDE_QUATERNION_DATA::ID),
33440 ATTITUDE_QUATERNION_COV_DATA::NAME => Some(ATTITUDE_QUATERNION_COV_DATA::ID),
33441 ATTITUDE_TARGET_DATA::NAME => Some(ATTITUDE_TARGET_DATA::ID),
33442 ATT_POS_MOCAP_DATA::NAME => Some(ATT_POS_MOCAP_DATA::ID),
33443 AUTH_KEY_DATA::NAME => Some(AUTH_KEY_DATA::ID),
33444 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::NAME => {
33445 Some(AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID)
33446 }
33447 AUTOPILOT_VERSION_DATA::NAME => Some(AUTOPILOT_VERSION_DATA::ID),
33448 AVAILABLE_MODES_DATA::NAME => Some(AVAILABLE_MODES_DATA::ID),
33449 AVAILABLE_MODES_MONITOR_DATA::NAME => Some(AVAILABLE_MODES_MONITOR_DATA::ID),
33450 BATTERY_INFO_DATA::NAME => Some(BATTERY_INFO_DATA::ID),
33451 BATTERY_STATUS_DATA::NAME => Some(BATTERY_STATUS_DATA::ID),
33452 BUTTON_CHANGE_DATA::NAME => Some(BUTTON_CHANGE_DATA::ID),
33453 CAMERA_CAPTURE_STATUS_DATA::NAME => Some(CAMERA_CAPTURE_STATUS_DATA::ID),
33454 CAMERA_FOV_STATUS_DATA::NAME => Some(CAMERA_FOV_STATUS_DATA::ID),
33455 CAMERA_IMAGE_CAPTURED_DATA::NAME => Some(CAMERA_IMAGE_CAPTURED_DATA::ID),
33456 CAMERA_INFORMATION_DATA::NAME => Some(CAMERA_INFORMATION_DATA::ID),
33457 CAMERA_SETTINGS_DATA::NAME => Some(CAMERA_SETTINGS_DATA::ID),
33458 CAMERA_THERMAL_RANGE_DATA::NAME => Some(CAMERA_THERMAL_RANGE_DATA::ID),
33459 CAMERA_TRACKING_GEO_STATUS_DATA::NAME => Some(CAMERA_TRACKING_GEO_STATUS_DATA::ID),
33460 CAMERA_TRACKING_IMAGE_STATUS_DATA::NAME => Some(CAMERA_TRACKING_IMAGE_STATUS_DATA::ID),
33461 CAMERA_TRIGGER_DATA::NAME => Some(CAMERA_TRIGGER_DATA::ID),
33462 CANFD_FRAME_DATA::NAME => Some(CANFD_FRAME_DATA::ID),
33463 CAN_FILTER_MODIFY_DATA::NAME => Some(CAN_FILTER_MODIFY_DATA::ID),
33464 CAN_FRAME_DATA::NAME => Some(CAN_FRAME_DATA::ID),
33465 CELLULAR_CONFIG_DATA::NAME => Some(CELLULAR_CONFIG_DATA::ID),
33466 CELLULAR_STATUS_DATA::NAME => Some(CELLULAR_STATUS_DATA::ID),
33467 CHANGE_OPERATOR_CONTROL_DATA::NAME => Some(CHANGE_OPERATOR_CONTROL_DATA::ID),
33468 CHANGE_OPERATOR_CONTROL_ACK_DATA::NAME => Some(CHANGE_OPERATOR_CONTROL_ACK_DATA::ID),
33469 COLLISION_DATA::NAME => Some(COLLISION_DATA::ID),
33470 COMMAND_ACK_DATA::NAME => Some(COMMAND_ACK_DATA::ID),
33471 COMMAND_CANCEL_DATA::NAME => Some(COMMAND_CANCEL_DATA::ID),
33472 COMMAND_INT_DATA::NAME => Some(COMMAND_INT_DATA::ID),
33473 COMMAND_LONG_DATA::NAME => Some(COMMAND_LONG_DATA::ID),
33474 COMPONENT_INFORMATION_DATA::NAME => Some(COMPONENT_INFORMATION_DATA::ID),
33475 COMPONENT_INFORMATION_BASIC_DATA::NAME => Some(COMPONENT_INFORMATION_BASIC_DATA::ID),
33476 COMPONENT_METADATA_DATA::NAME => Some(COMPONENT_METADATA_DATA::ID),
33477 CONTROL_SYSTEM_STATE_DATA::NAME => Some(CONTROL_SYSTEM_STATE_DATA::ID),
33478 CURRENT_EVENT_SEQUENCE_DATA::NAME => Some(CURRENT_EVENT_SEQUENCE_DATA::ID),
33479 CURRENT_MODE_DATA::NAME => Some(CURRENT_MODE_DATA::ID),
33480 DATA_STREAM_DATA::NAME => Some(DATA_STREAM_DATA::ID),
33481 DATA_TRANSMISSION_HANDSHAKE_DATA::NAME => Some(DATA_TRANSMISSION_HANDSHAKE_DATA::ID),
33482 DEBUG_DATA::NAME => Some(DEBUG_DATA::ID),
33483 DEBUG_FLOAT_ARRAY_DATA::NAME => Some(DEBUG_FLOAT_ARRAY_DATA::ID),
33484 DEBUG_VECT_DATA::NAME => Some(DEBUG_VECT_DATA::ID),
33485 DISTANCE_SENSOR_DATA::NAME => Some(DISTANCE_SENSOR_DATA::ID),
33486 EFI_STATUS_DATA::NAME => Some(EFI_STATUS_DATA::ID),
33487 ENCAPSULATED_DATA_DATA::NAME => Some(ENCAPSULATED_DATA_DATA::ID),
33488 ESC_INFO_DATA::NAME => Some(ESC_INFO_DATA::ID),
33489 ESC_STATUS_DATA::NAME => Some(ESC_STATUS_DATA::ID),
33490 ESTIMATOR_STATUS_DATA::NAME => Some(ESTIMATOR_STATUS_DATA::ID),
33491 EVENT_DATA::NAME => Some(EVENT_DATA::ID),
33492 EXTENDED_SYS_STATE_DATA::NAME => Some(EXTENDED_SYS_STATE_DATA::ID),
33493 FENCE_STATUS_DATA::NAME => Some(FENCE_STATUS_DATA::ID),
33494 FILE_TRANSFER_PROTOCOL_DATA::NAME => Some(FILE_TRANSFER_PROTOCOL_DATA::ID),
33495 FLIGHT_INFORMATION_DATA::NAME => Some(FLIGHT_INFORMATION_DATA::ID),
33496 FOLLOW_TARGET_DATA::NAME => Some(FOLLOW_TARGET_DATA::ID),
33497 FUEL_STATUS_DATA::NAME => Some(FUEL_STATUS_DATA::ID),
33498 GENERATOR_STATUS_DATA::NAME => Some(GENERATOR_STATUS_DATA::ID),
33499 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::NAME => {
33500 Some(GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID)
33501 }
33502 GIMBAL_DEVICE_INFORMATION_DATA::NAME => Some(GIMBAL_DEVICE_INFORMATION_DATA::ID),
33503 GIMBAL_DEVICE_SET_ATTITUDE_DATA::NAME => Some(GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID),
33504 GIMBAL_MANAGER_INFORMATION_DATA::NAME => Some(GIMBAL_MANAGER_INFORMATION_DATA::ID),
33505 GIMBAL_MANAGER_SET_ATTITUDE_DATA::NAME => Some(GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID),
33506 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::NAME => {
33507 Some(GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID)
33508 }
33509 GIMBAL_MANAGER_SET_PITCHYAW_DATA::NAME => Some(GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID),
33510 GIMBAL_MANAGER_STATUS_DATA::NAME => Some(GIMBAL_MANAGER_STATUS_DATA::ID),
33511 GLOBAL_POSITION_INT_DATA::NAME => Some(GLOBAL_POSITION_INT_DATA::ID),
33512 GLOBAL_POSITION_INT_COV_DATA::NAME => Some(GLOBAL_POSITION_INT_COV_DATA::ID),
33513 GLOBAL_VISION_POSITION_ESTIMATE_DATA::NAME => {
33514 Some(GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID)
33515 }
33516 GPS2_RAW_DATA::NAME => Some(GPS2_RAW_DATA::ID),
33517 GPS2_RTK_DATA::NAME => Some(GPS2_RTK_DATA::ID),
33518 GPS_GLOBAL_ORIGIN_DATA::NAME => Some(GPS_GLOBAL_ORIGIN_DATA::ID),
33519 GPS_INJECT_DATA_DATA::NAME => Some(GPS_INJECT_DATA_DATA::ID),
33520 GPS_INPUT_DATA::NAME => Some(GPS_INPUT_DATA::ID),
33521 GPS_RAW_INT_DATA::NAME => Some(GPS_RAW_INT_DATA::ID),
33522 GPS_RTCM_DATA_DATA::NAME => Some(GPS_RTCM_DATA_DATA::ID),
33523 GPS_RTK_DATA::NAME => Some(GPS_RTK_DATA::ID),
33524 GPS_STATUS_DATA::NAME => Some(GPS_STATUS_DATA::ID),
33525 HEARTBEAT_DATA::NAME => Some(HEARTBEAT_DATA::ID),
33526 HIGHRES_IMU_DATA::NAME => Some(HIGHRES_IMU_DATA::ID),
33527 HIGH_LATENCY_DATA::NAME => Some(HIGH_LATENCY_DATA::ID),
33528 HIGH_LATENCY2_DATA::NAME => Some(HIGH_LATENCY2_DATA::ID),
33529 HIL_ACTUATOR_CONTROLS_DATA::NAME => Some(HIL_ACTUATOR_CONTROLS_DATA::ID),
33530 HIL_CONTROLS_DATA::NAME => Some(HIL_CONTROLS_DATA::ID),
33531 HIL_GPS_DATA::NAME => Some(HIL_GPS_DATA::ID),
33532 HIL_OPTICAL_FLOW_DATA::NAME => Some(HIL_OPTICAL_FLOW_DATA::ID),
33533 HIL_RC_INPUTS_RAW_DATA::NAME => Some(HIL_RC_INPUTS_RAW_DATA::ID),
33534 HIL_SENSOR_DATA::NAME => Some(HIL_SENSOR_DATA::ID),
33535 HIL_STATE_DATA::NAME => Some(HIL_STATE_DATA::ID),
33536 HIL_STATE_QUATERNION_DATA::NAME => Some(HIL_STATE_QUATERNION_DATA::ID),
33537 HOME_POSITION_DATA::NAME => Some(HOME_POSITION_DATA::ID),
33538 HYGROMETER_SENSOR_DATA::NAME => Some(HYGROMETER_SENSOR_DATA::ID),
33539 ILLUMINATOR_STATUS_DATA::NAME => Some(ILLUMINATOR_STATUS_DATA::ID),
33540 ISBD_LINK_STATUS_DATA::NAME => Some(ISBD_LINK_STATUS_DATA::ID),
33541 LANDING_TARGET_DATA::NAME => Some(LANDING_TARGET_DATA::ID),
33542 LINK_NODE_STATUS_DATA::NAME => Some(LINK_NODE_STATUS_DATA::ID),
33543 LOCAL_POSITION_NED_DATA::NAME => Some(LOCAL_POSITION_NED_DATA::ID),
33544 LOCAL_POSITION_NED_COV_DATA::NAME => Some(LOCAL_POSITION_NED_COV_DATA::ID),
33545 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::NAME => {
33546 Some(LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID)
33547 }
33548 LOGGING_ACK_DATA::NAME => Some(LOGGING_ACK_DATA::ID),
33549 LOGGING_DATA_DATA::NAME => Some(LOGGING_DATA_DATA::ID),
33550 LOGGING_DATA_ACKED_DATA::NAME => Some(LOGGING_DATA_ACKED_DATA::ID),
33551 LOG_DATA_DATA::NAME => Some(LOG_DATA_DATA::ID),
33552 LOG_ENTRY_DATA::NAME => Some(LOG_ENTRY_DATA::ID),
33553 LOG_ERASE_DATA::NAME => Some(LOG_ERASE_DATA::ID),
33554 LOG_REQUEST_DATA_DATA::NAME => Some(LOG_REQUEST_DATA_DATA::ID),
33555 LOG_REQUEST_END_DATA::NAME => Some(LOG_REQUEST_END_DATA::ID),
33556 LOG_REQUEST_LIST_DATA::NAME => Some(LOG_REQUEST_LIST_DATA::ID),
33557 MAG_CAL_REPORT_DATA::NAME => Some(MAG_CAL_REPORT_DATA::ID),
33558 MANUAL_CONTROL_DATA::NAME => Some(MANUAL_CONTROL_DATA::ID),
33559 MANUAL_SETPOINT_DATA::NAME => Some(MANUAL_SETPOINT_DATA::ID),
33560 MEMORY_VECT_DATA::NAME => Some(MEMORY_VECT_DATA::ID),
33561 MESSAGE_INTERVAL_DATA::NAME => Some(MESSAGE_INTERVAL_DATA::ID),
33562 MISSION_ACK_DATA::NAME => Some(MISSION_ACK_DATA::ID),
33563 MISSION_CLEAR_ALL_DATA::NAME => Some(MISSION_CLEAR_ALL_DATA::ID),
33564 MISSION_COUNT_DATA::NAME => Some(MISSION_COUNT_DATA::ID),
33565 MISSION_CURRENT_DATA::NAME => Some(MISSION_CURRENT_DATA::ID),
33566 MISSION_ITEM_DATA::NAME => Some(MISSION_ITEM_DATA::ID),
33567 MISSION_ITEM_INT_DATA::NAME => Some(MISSION_ITEM_INT_DATA::ID),
33568 MISSION_ITEM_REACHED_DATA::NAME => Some(MISSION_ITEM_REACHED_DATA::ID),
33569 MISSION_REQUEST_DATA::NAME => Some(MISSION_REQUEST_DATA::ID),
33570 MISSION_REQUEST_INT_DATA::NAME => Some(MISSION_REQUEST_INT_DATA::ID),
33571 MISSION_REQUEST_LIST_DATA::NAME => Some(MISSION_REQUEST_LIST_DATA::ID),
33572 MISSION_REQUEST_PARTIAL_LIST_DATA::NAME => Some(MISSION_REQUEST_PARTIAL_LIST_DATA::ID),
33573 MISSION_SET_CURRENT_DATA::NAME => Some(MISSION_SET_CURRENT_DATA::ID),
33574 MISSION_WRITE_PARTIAL_LIST_DATA::NAME => Some(MISSION_WRITE_PARTIAL_LIST_DATA::ID),
33575 MOUNT_ORIENTATION_DATA::NAME => Some(MOUNT_ORIENTATION_DATA::ID),
33576 NAMED_VALUE_FLOAT_DATA::NAME => Some(NAMED_VALUE_FLOAT_DATA::ID),
33577 NAMED_VALUE_INT_DATA::NAME => Some(NAMED_VALUE_INT_DATA::ID),
33578 NAV_CONTROLLER_OUTPUT_DATA::NAME => Some(NAV_CONTROLLER_OUTPUT_DATA::ID),
33579 OBSTACLE_DISTANCE_DATA::NAME => Some(OBSTACLE_DISTANCE_DATA::ID),
33580 ODOMETRY_DATA::NAME => Some(ODOMETRY_DATA::ID),
33581 ONBOARD_COMPUTER_STATUS_DATA::NAME => Some(ONBOARD_COMPUTER_STATUS_DATA::ID),
33582 OPEN_DRONE_ID_ARM_STATUS_DATA::NAME => Some(OPEN_DRONE_ID_ARM_STATUS_DATA::ID),
33583 OPEN_DRONE_ID_AUTHENTICATION_DATA::NAME => Some(OPEN_DRONE_ID_AUTHENTICATION_DATA::ID),
33584 OPEN_DRONE_ID_BASIC_ID_DATA::NAME => Some(OPEN_DRONE_ID_BASIC_ID_DATA::ID),
33585 OPEN_DRONE_ID_LOCATION_DATA::NAME => Some(OPEN_DRONE_ID_LOCATION_DATA::ID),
33586 OPEN_DRONE_ID_MESSAGE_PACK_DATA::NAME => Some(OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID),
33587 OPEN_DRONE_ID_OPERATOR_ID_DATA::NAME => Some(OPEN_DRONE_ID_OPERATOR_ID_DATA::ID),
33588 OPEN_DRONE_ID_SELF_ID_DATA::NAME => Some(OPEN_DRONE_ID_SELF_ID_DATA::ID),
33589 OPEN_DRONE_ID_SYSTEM_DATA::NAME => Some(OPEN_DRONE_ID_SYSTEM_DATA::ID),
33590 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::NAME => Some(OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID),
33591 OPTICAL_FLOW_DATA::NAME => Some(OPTICAL_FLOW_DATA::ID),
33592 OPTICAL_FLOW_RAD_DATA::NAME => Some(OPTICAL_FLOW_RAD_DATA::ID),
33593 ORBIT_EXECUTION_STATUS_DATA::NAME => Some(ORBIT_EXECUTION_STATUS_DATA::ID),
33594 PARAM_EXT_ACK_DATA::NAME => Some(PARAM_EXT_ACK_DATA::ID),
33595 PARAM_EXT_REQUEST_LIST_DATA::NAME => Some(PARAM_EXT_REQUEST_LIST_DATA::ID),
33596 PARAM_EXT_REQUEST_READ_DATA::NAME => Some(PARAM_EXT_REQUEST_READ_DATA::ID),
33597 PARAM_EXT_SET_DATA::NAME => Some(PARAM_EXT_SET_DATA::ID),
33598 PARAM_EXT_VALUE_DATA::NAME => Some(PARAM_EXT_VALUE_DATA::ID),
33599 PARAM_MAP_RC_DATA::NAME => Some(PARAM_MAP_RC_DATA::ID),
33600 PARAM_REQUEST_LIST_DATA::NAME => Some(PARAM_REQUEST_LIST_DATA::ID),
33601 PARAM_REQUEST_READ_DATA::NAME => Some(PARAM_REQUEST_READ_DATA::ID),
33602 PARAM_SET_DATA::NAME => Some(PARAM_SET_DATA::ID),
33603 PARAM_VALUE_DATA::NAME => Some(PARAM_VALUE_DATA::ID),
33604 PING_DATA::NAME => Some(PING_DATA::ID),
33605 PLAY_TUNE_DATA::NAME => Some(PLAY_TUNE_DATA::ID),
33606 PLAY_TUNE_V2_DATA::NAME => Some(PLAY_TUNE_V2_DATA::ID),
33607 POSITION_TARGET_GLOBAL_INT_DATA::NAME => Some(POSITION_TARGET_GLOBAL_INT_DATA::ID),
33608 POSITION_TARGET_LOCAL_NED_DATA::NAME => Some(POSITION_TARGET_LOCAL_NED_DATA::ID),
33609 POWER_STATUS_DATA::NAME => Some(POWER_STATUS_DATA::ID),
33610 PROTOCOL_VERSION_DATA::NAME => Some(PROTOCOL_VERSION_DATA::ID),
33611 RADIO_STATUS_DATA::NAME => Some(RADIO_STATUS_DATA::ID),
33612 RAW_IMU_DATA::NAME => Some(RAW_IMU_DATA::ID),
33613 RAW_PRESSURE_DATA::NAME => Some(RAW_PRESSURE_DATA::ID),
33614 RAW_RPM_DATA::NAME => Some(RAW_RPM_DATA::ID),
33615 RC_CHANNELS_DATA::NAME => Some(RC_CHANNELS_DATA::ID),
33616 RC_CHANNELS_OVERRIDE_DATA::NAME => Some(RC_CHANNELS_OVERRIDE_DATA::ID),
33617 RC_CHANNELS_RAW_DATA::NAME => Some(RC_CHANNELS_RAW_DATA::ID),
33618 RC_CHANNELS_SCALED_DATA::NAME => Some(RC_CHANNELS_SCALED_DATA::ID),
33619 REQUEST_DATA_STREAM_DATA::NAME => Some(REQUEST_DATA_STREAM_DATA::ID),
33620 REQUEST_EVENT_DATA::NAME => Some(REQUEST_EVENT_DATA::ID),
33621 RESOURCE_REQUEST_DATA::NAME => Some(RESOURCE_REQUEST_DATA::ID),
33622 RESPONSE_EVENT_ERROR_DATA::NAME => Some(RESPONSE_EVENT_ERROR_DATA::ID),
33623 SAFETY_ALLOWED_AREA_DATA::NAME => Some(SAFETY_ALLOWED_AREA_DATA::ID),
33624 SAFETY_SET_ALLOWED_AREA_DATA::NAME => Some(SAFETY_SET_ALLOWED_AREA_DATA::ID),
33625 SCALED_IMU_DATA::NAME => Some(SCALED_IMU_DATA::ID),
33626 SCALED_IMU2_DATA::NAME => Some(SCALED_IMU2_DATA::ID),
33627 SCALED_IMU3_DATA::NAME => Some(SCALED_IMU3_DATA::ID),
33628 SCALED_PRESSURE_DATA::NAME => Some(SCALED_PRESSURE_DATA::ID),
33629 SCALED_PRESSURE2_DATA::NAME => Some(SCALED_PRESSURE2_DATA::ID),
33630 SCALED_PRESSURE3_DATA::NAME => Some(SCALED_PRESSURE3_DATA::ID),
33631 SERIAL_CONTROL_DATA::NAME => Some(SERIAL_CONTROL_DATA::ID),
33632 SERVO_OUTPUT_RAW_DATA::NAME => Some(SERVO_OUTPUT_RAW_DATA::ID),
33633 SETUP_SIGNING_DATA::NAME => Some(SETUP_SIGNING_DATA::ID),
33634 SET_ACTUATOR_CONTROL_TARGET_DATA::NAME => Some(SET_ACTUATOR_CONTROL_TARGET_DATA::ID),
33635 SET_ATTITUDE_TARGET_DATA::NAME => Some(SET_ATTITUDE_TARGET_DATA::ID),
33636 SET_GPS_GLOBAL_ORIGIN_DATA::NAME => Some(SET_GPS_GLOBAL_ORIGIN_DATA::ID),
33637 SET_HOME_POSITION_DATA::NAME => Some(SET_HOME_POSITION_DATA::ID),
33638 SET_MODE_DATA::NAME => Some(SET_MODE_DATA::ID),
33639 SET_POSITION_TARGET_GLOBAL_INT_DATA::NAME => {
33640 Some(SET_POSITION_TARGET_GLOBAL_INT_DATA::ID)
33641 }
33642 SET_POSITION_TARGET_LOCAL_NED_DATA::NAME => {
33643 Some(SET_POSITION_TARGET_LOCAL_NED_DATA::ID)
33644 }
33645 SIM_STATE_DATA::NAME => Some(SIM_STATE_DATA::ID),
33646 SMART_BATTERY_INFO_DATA::NAME => Some(SMART_BATTERY_INFO_DATA::ID),
33647 STATUSTEXT_DATA::NAME => Some(STATUSTEXT_DATA::ID),
33648 STORAGE_INFORMATION_DATA::NAME => Some(STORAGE_INFORMATION_DATA::ID),
33649 SUPPORTED_TUNES_DATA::NAME => Some(SUPPORTED_TUNES_DATA::ID),
33650 SYSTEM_TIME_DATA::NAME => Some(SYSTEM_TIME_DATA::ID),
33651 SYS_STATUS_DATA::NAME => Some(SYS_STATUS_DATA::ID),
33652 TERRAIN_CHECK_DATA::NAME => Some(TERRAIN_CHECK_DATA::ID),
33653 TERRAIN_DATA_DATA::NAME => Some(TERRAIN_DATA_DATA::ID),
33654 TERRAIN_REPORT_DATA::NAME => Some(TERRAIN_REPORT_DATA::ID),
33655 TERRAIN_REQUEST_DATA::NAME => Some(TERRAIN_REQUEST_DATA::ID),
33656 TIMESYNC_DATA::NAME => Some(TIMESYNC_DATA::ID),
33657 TIME_ESTIMATE_TO_TARGET_DATA::NAME => Some(TIME_ESTIMATE_TO_TARGET_DATA::ID),
33658 TRAJECTORY_REPRESENTATION_BEZIER_DATA::NAME => {
33659 Some(TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID)
33660 }
33661 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::NAME => {
33662 Some(TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID)
33663 }
33664 TUNNEL_DATA::NAME => Some(TUNNEL_DATA::ID),
33665 UAVCAN_NODE_INFO_DATA::NAME => Some(UAVCAN_NODE_INFO_DATA::ID),
33666 UAVCAN_NODE_STATUS_DATA::NAME => Some(UAVCAN_NODE_STATUS_DATA::ID),
33667 UAVIONIX_ADSB_GET_DATA::NAME => Some(UAVIONIX_ADSB_GET_DATA::ID),
33668 UAVIONIX_ADSB_OUT_CFG_DATA::NAME => Some(UAVIONIX_ADSB_OUT_CFG_DATA::ID),
33669 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::NAME => {
33670 Some(UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::ID)
33671 }
33672 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::NAME => {
33673 Some(UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::ID)
33674 }
33675 UAVIONIX_ADSB_OUT_CONTROL_DATA::NAME => Some(UAVIONIX_ADSB_OUT_CONTROL_DATA::ID),
33676 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::NAME => Some(UAVIONIX_ADSB_OUT_DYNAMIC_DATA::ID),
33677 UAVIONIX_ADSB_OUT_STATUS_DATA::NAME => Some(UAVIONIX_ADSB_OUT_STATUS_DATA::ID),
33678 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::NAME => {
33679 Some(UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::ID)
33680 }
33681 UTM_GLOBAL_POSITION_DATA::NAME => Some(UTM_GLOBAL_POSITION_DATA::ID),
33682 V2_EXTENSION_DATA::NAME => Some(V2_EXTENSION_DATA::ID),
33683 VFR_HUD_DATA::NAME => Some(VFR_HUD_DATA::ID),
33684 VIBRATION_DATA::NAME => Some(VIBRATION_DATA::ID),
33685 VICON_POSITION_ESTIMATE_DATA::NAME => Some(VICON_POSITION_ESTIMATE_DATA::ID),
33686 VIDEO_STREAM_INFORMATION_DATA::NAME => Some(VIDEO_STREAM_INFORMATION_DATA::ID),
33687 VIDEO_STREAM_STATUS_DATA::NAME => Some(VIDEO_STREAM_STATUS_DATA::ID),
33688 VISION_POSITION_ESTIMATE_DATA::NAME => Some(VISION_POSITION_ESTIMATE_DATA::ID),
33689 VISION_SPEED_ESTIMATE_DATA::NAME => Some(VISION_SPEED_ESTIMATE_DATA::ID),
33690 WHEEL_DISTANCE_DATA::NAME => Some(WHEEL_DISTANCE_DATA::ID),
33691 WIFI_CONFIG_AP_DATA::NAME => Some(WIFI_CONFIG_AP_DATA::ID),
33692 WINCH_STATUS_DATA::NAME => Some(WINCH_STATUS_DATA::ID),
33693 WIND_COV_DATA::NAME => Some(WIND_COV_DATA::ID),
33694 _ => None,
33695 }
33696 }
33697 fn default_message_from_id(id: u32) -> Option<Self> {
33698 match id {
33699 ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::ACTUATOR_CONTROL_TARGET(
33700 ACTUATOR_CONTROL_TARGET_DATA::default(),
33701 )),
33702 ACTUATOR_OUTPUT_STATUS_DATA::ID => Some(Self::ACTUATOR_OUTPUT_STATUS(
33703 ACTUATOR_OUTPUT_STATUS_DATA::default(),
33704 )),
33705 ADSB_VEHICLE_DATA::ID => Some(Self::ADSB_VEHICLE(ADSB_VEHICLE_DATA::default())),
33706 AIS_VESSEL_DATA::ID => Some(Self::AIS_VESSEL(AIS_VESSEL_DATA::default())),
33707 ALTITUDE_DATA::ID => Some(Self::ALTITUDE(ALTITUDE_DATA::default())),
33708 ATTITUDE_DATA::ID => Some(Self::ATTITUDE(ATTITUDE_DATA::default())),
33709 ATTITUDE_QUATERNION_DATA::ID => Some(Self::ATTITUDE_QUATERNION(
33710 ATTITUDE_QUATERNION_DATA::default(),
33711 )),
33712 ATTITUDE_QUATERNION_COV_DATA::ID => Some(Self::ATTITUDE_QUATERNION_COV(
33713 ATTITUDE_QUATERNION_COV_DATA::default(),
33714 )),
33715 ATTITUDE_TARGET_DATA::ID => {
33716 Some(Self::ATTITUDE_TARGET(ATTITUDE_TARGET_DATA::default()))
33717 }
33718 ATT_POS_MOCAP_DATA::ID => Some(Self::ATT_POS_MOCAP(ATT_POS_MOCAP_DATA::default())),
33719 AUTH_KEY_DATA::ID => Some(Self::AUTH_KEY(AUTH_KEY_DATA::default())),
33720 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
33721 Some(Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(
33722 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::default(),
33723 ))
33724 }
33725 AUTOPILOT_VERSION_DATA::ID => {
33726 Some(Self::AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA::default()))
33727 }
33728 AVAILABLE_MODES_DATA::ID => {
33729 Some(Self::AVAILABLE_MODES(AVAILABLE_MODES_DATA::default()))
33730 }
33731 AVAILABLE_MODES_MONITOR_DATA::ID => Some(Self::AVAILABLE_MODES_MONITOR(
33732 AVAILABLE_MODES_MONITOR_DATA::default(),
33733 )),
33734 BATTERY_INFO_DATA::ID => Some(Self::BATTERY_INFO(BATTERY_INFO_DATA::default())),
33735 BATTERY_STATUS_DATA::ID => Some(Self::BATTERY_STATUS(BATTERY_STATUS_DATA::default())),
33736 BUTTON_CHANGE_DATA::ID => Some(Self::BUTTON_CHANGE(BUTTON_CHANGE_DATA::default())),
33737 CAMERA_CAPTURE_STATUS_DATA::ID => Some(Self::CAMERA_CAPTURE_STATUS(
33738 CAMERA_CAPTURE_STATUS_DATA::default(),
33739 )),
33740 CAMERA_FOV_STATUS_DATA::ID => {
33741 Some(Self::CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA::default()))
33742 }
33743 CAMERA_IMAGE_CAPTURED_DATA::ID => Some(Self::CAMERA_IMAGE_CAPTURED(
33744 CAMERA_IMAGE_CAPTURED_DATA::default(),
33745 )),
33746 CAMERA_INFORMATION_DATA::ID => {
33747 Some(Self::CAMERA_INFORMATION(CAMERA_INFORMATION_DATA::default()))
33748 }
33749 CAMERA_SETTINGS_DATA::ID => {
33750 Some(Self::CAMERA_SETTINGS(CAMERA_SETTINGS_DATA::default()))
33751 }
33752 CAMERA_THERMAL_RANGE_DATA::ID => Some(Self::CAMERA_THERMAL_RANGE(
33753 CAMERA_THERMAL_RANGE_DATA::default(),
33754 )),
33755 CAMERA_TRACKING_GEO_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_GEO_STATUS(
33756 CAMERA_TRACKING_GEO_STATUS_DATA::default(),
33757 )),
33758 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_IMAGE_STATUS(
33759 CAMERA_TRACKING_IMAGE_STATUS_DATA::default(),
33760 )),
33761 CAMERA_TRIGGER_DATA::ID => Some(Self::CAMERA_TRIGGER(CAMERA_TRIGGER_DATA::default())),
33762 CANFD_FRAME_DATA::ID => Some(Self::CANFD_FRAME(CANFD_FRAME_DATA::default())),
33763 CAN_FILTER_MODIFY_DATA::ID => {
33764 Some(Self::CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA::default()))
33765 }
33766 CAN_FRAME_DATA::ID => Some(Self::CAN_FRAME(CAN_FRAME_DATA::default())),
33767 CELLULAR_CONFIG_DATA::ID => {
33768 Some(Self::CELLULAR_CONFIG(CELLULAR_CONFIG_DATA::default()))
33769 }
33770 CELLULAR_STATUS_DATA::ID => {
33771 Some(Self::CELLULAR_STATUS(CELLULAR_STATUS_DATA::default()))
33772 }
33773 CHANGE_OPERATOR_CONTROL_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL(
33774 CHANGE_OPERATOR_CONTROL_DATA::default(),
33775 )),
33776 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL_ACK(
33777 CHANGE_OPERATOR_CONTROL_ACK_DATA::default(),
33778 )),
33779 COLLISION_DATA::ID => Some(Self::COLLISION(COLLISION_DATA::default())),
33780 COMMAND_ACK_DATA::ID => Some(Self::COMMAND_ACK(COMMAND_ACK_DATA::default())),
33781 COMMAND_CANCEL_DATA::ID => Some(Self::COMMAND_CANCEL(COMMAND_CANCEL_DATA::default())),
33782 COMMAND_INT_DATA::ID => Some(Self::COMMAND_INT(COMMAND_INT_DATA::default())),
33783 COMMAND_LONG_DATA::ID => Some(Self::COMMAND_LONG(COMMAND_LONG_DATA::default())),
33784 COMPONENT_INFORMATION_DATA::ID => Some(Self::COMPONENT_INFORMATION(
33785 COMPONENT_INFORMATION_DATA::default(),
33786 )),
33787 COMPONENT_INFORMATION_BASIC_DATA::ID => Some(Self::COMPONENT_INFORMATION_BASIC(
33788 COMPONENT_INFORMATION_BASIC_DATA::default(),
33789 )),
33790 COMPONENT_METADATA_DATA::ID => {
33791 Some(Self::COMPONENT_METADATA(COMPONENT_METADATA_DATA::default()))
33792 }
33793 CONTROL_SYSTEM_STATE_DATA::ID => Some(Self::CONTROL_SYSTEM_STATE(
33794 CONTROL_SYSTEM_STATE_DATA::default(),
33795 )),
33796 CURRENT_EVENT_SEQUENCE_DATA::ID => Some(Self::CURRENT_EVENT_SEQUENCE(
33797 CURRENT_EVENT_SEQUENCE_DATA::default(),
33798 )),
33799 CURRENT_MODE_DATA::ID => Some(Self::CURRENT_MODE(CURRENT_MODE_DATA::default())),
33800 DATA_STREAM_DATA::ID => Some(Self::DATA_STREAM(DATA_STREAM_DATA::default())),
33801 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => Some(Self::DATA_TRANSMISSION_HANDSHAKE(
33802 DATA_TRANSMISSION_HANDSHAKE_DATA::default(),
33803 )),
33804 DEBUG_DATA::ID => Some(Self::DEBUG(DEBUG_DATA::default())),
33805 DEBUG_FLOAT_ARRAY_DATA::ID => {
33806 Some(Self::DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA::default()))
33807 }
33808 DEBUG_VECT_DATA::ID => Some(Self::DEBUG_VECT(DEBUG_VECT_DATA::default())),
33809 DISTANCE_SENSOR_DATA::ID => {
33810 Some(Self::DISTANCE_SENSOR(DISTANCE_SENSOR_DATA::default()))
33811 }
33812 EFI_STATUS_DATA::ID => Some(Self::EFI_STATUS(EFI_STATUS_DATA::default())),
33813 ENCAPSULATED_DATA_DATA::ID => {
33814 Some(Self::ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA::default()))
33815 }
33816 ESC_INFO_DATA::ID => Some(Self::ESC_INFO(ESC_INFO_DATA::default())),
33817 ESC_STATUS_DATA::ID => Some(Self::ESC_STATUS(ESC_STATUS_DATA::default())),
33818 ESTIMATOR_STATUS_DATA::ID => {
33819 Some(Self::ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA::default()))
33820 }
33821 EVENT_DATA::ID => Some(Self::EVENT(EVENT_DATA::default())),
33822 EXTENDED_SYS_STATE_DATA::ID => {
33823 Some(Self::EXTENDED_SYS_STATE(EXTENDED_SYS_STATE_DATA::default()))
33824 }
33825 FENCE_STATUS_DATA::ID => Some(Self::FENCE_STATUS(FENCE_STATUS_DATA::default())),
33826 FILE_TRANSFER_PROTOCOL_DATA::ID => Some(Self::FILE_TRANSFER_PROTOCOL(
33827 FILE_TRANSFER_PROTOCOL_DATA::default(),
33828 )),
33829 FLIGHT_INFORMATION_DATA::ID => {
33830 Some(Self::FLIGHT_INFORMATION(FLIGHT_INFORMATION_DATA::default()))
33831 }
33832 FOLLOW_TARGET_DATA::ID => Some(Self::FOLLOW_TARGET(FOLLOW_TARGET_DATA::default())),
33833 FUEL_STATUS_DATA::ID => Some(Self::FUEL_STATUS(FUEL_STATUS_DATA::default())),
33834 GENERATOR_STATUS_DATA::ID => {
33835 Some(Self::GENERATOR_STATUS(GENERATOR_STATUS_DATA::default()))
33836 }
33837 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => Some(Self::GIMBAL_DEVICE_ATTITUDE_STATUS(
33838 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::default(),
33839 )),
33840 GIMBAL_DEVICE_INFORMATION_DATA::ID => Some(Self::GIMBAL_DEVICE_INFORMATION(
33841 GIMBAL_DEVICE_INFORMATION_DATA::default(),
33842 )),
33843 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_DEVICE_SET_ATTITUDE(
33844 GIMBAL_DEVICE_SET_ATTITUDE_DATA::default(),
33845 )),
33846 GIMBAL_MANAGER_INFORMATION_DATA::ID => Some(Self::GIMBAL_MANAGER_INFORMATION(
33847 GIMBAL_MANAGER_INFORMATION_DATA::default(),
33848 )),
33849 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_ATTITUDE(
33850 GIMBAL_MANAGER_SET_ATTITUDE_DATA::default(),
33851 )),
33852 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
33853 Some(Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(
33854 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::default(),
33855 ))
33856 }
33857 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_PITCHYAW(
33858 GIMBAL_MANAGER_SET_PITCHYAW_DATA::default(),
33859 )),
33860 GIMBAL_MANAGER_STATUS_DATA::ID => Some(Self::GIMBAL_MANAGER_STATUS(
33861 GIMBAL_MANAGER_STATUS_DATA::default(),
33862 )),
33863 GLOBAL_POSITION_INT_DATA::ID => Some(Self::GLOBAL_POSITION_INT(
33864 GLOBAL_POSITION_INT_DATA::default(),
33865 )),
33866 GLOBAL_POSITION_INT_COV_DATA::ID => Some(Self::GLOBAL_POSITION_INT_COV(
33867 GLOBAL_POSITION_INT_COV_DATA::default(),
33868 )),
33869 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
33870 Some(Self::GLOBAL_VISION_POSITION_ESTIMATE(
33871 GLOBAL_VISION_POSITION_ESTIMATE_DATA::default(),
33872 ))
33873 }
33874 GPS2_RAW_DATA::ID => Some(Self::GPS2_RAW(GPS2_RAW_DATA::default())),
33875 GPS2_RTK_DATA::ID => Some(Self::GPS2_RTK(GPS2_RTK_DATA::default())),
33876 GPS_GLOBAL_ORIGIN_DATA::ID => {
33877 Some(Self::GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA::default()))
33878 }
33879 GPS_INJECT_DATA_DATA::ID => {
33880 Some(Self::GPS_INJECT_DATA(GPS_INJECT_DATA_DATA::default()))
33881 }
33882 GPS_INPUT_DATA::ID => Some(Self::GPS_INPUT(GPS_INPUT_DATA::default())),
33883 GPS_RAW_INT_DATA::ID => Some(Self::GPS_RAW_INT(GPS_RAW_INT_DATA::default())),
33884 GPS_RTCM_DATA_DATA::ID => Some(Self::GPS_RTCM_DATA(GPS_RTCM_DATA_DATA::default())),
33885 GPS_RTK_DATA::ID => Some(Self::GPS_RTK(GPS_RTK_DATA::default())),
33886 GPS_STATUS_DATA::ID => Some(Self::GPS_STATUS(GPS_STATUS_DATA::default())),
33887 HEARTBEAT_DATA::ID => Some(Self::HEARTBEAT(HEARTBEAT_DATA::default())),
33888 HIGHRES_IMU_DATA::ID => Some(Self::HIGHRES_IMU(HIGHRES_IMU_DATA::default())),
33889 HIGH_LATENCY_DATA::ID => Some(Self::HIGH_LATENCY(HIGH_LATENCY_DATA::default())),
33890 HIGH_LATENCY2_DATA::ID => Some(Self::HIGH_LATENCY2(HIGH_LATENCY2_DATA::default())),
33891 HIL_ACTUATOR_CONTROLS_DATA::ID => Some(Self::HIL_ACTUATOR_CONTROLS(
33892 HIL_ACTUATOR_CONTROLS_DATA::default(),
33893 )),
33894 HIL_CONTROLS_DATA::ID => Some(Self::HIL_CONTROLS(HIL_CONTROLS_DATA::default())),
33895 HIL_GPS_DATA::ID => Some(Self::HIL_GPS(HIL_GPS_DATA::default())),
33896 HIL_OPTICAL_FLOW_DATA::ID => {
33897 Some(Self::HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA::default()))
33898 }
33899 HIL_RC_INPUTS_RAW_DATA::ID => {
33900 Some(Self::HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA::default()))
33901 }
33902 HIL_SENSOR_DATA::ID => Some(Self::HIL_SENSOR(HIL_SENSOR_DATA::default())),
33903 HIL_STATE_DATA::ID => Some(Self::HIL_STATE(HIL_STATE_DATA::default())),
33904 HIL_STATE_QUATERNION_DATA::ID => Some(Self::HIL_STATE_QUATERNION(
33905 HIL_STATE_QUATERNION_DATA::default(),
33906 )),
33907 HOME_POSITION_DATA::ID => Some(Self::HOME_POSITION(HOME_POSITION_DATA::default())),
33908 HYGROMETER_SENSOR_DATA::ID => {
33909 Some(Self::HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA::default()))
33910 }
33911 ILLUMINATOR_STATUS_DATA::ID => {
33912 Some(Self::ILLUMINATOR_STATUS(ILLUMINATOR_STATUS_DATA::default()))
33913 }
33914 ISBD_LINK_STATUS_DATA::ID => {
33915 Some(Self::ISBD_LINK_STATUS(ISBD_LINK_STATUS_DATA::default()))
33916 }
33917 LANDING_TARGET_DATA::ID => Some(Self::LANDING_TARGET(LANDING_TARGET_DATA::default())),
33918 LINK_NODE_STATUS_DATA::ID => {
33919 Some(Self::LINK_NODE_STATUS(LINK_NODE_STATUS_DATA::default()))
33920 }
33921 LOCAL_POSITION_NED_DATA::ID => {
33922 Some(Self::LOCAL_POSITION_NED(LOCAL_POSITION_NED_DATA::default()))
33923 }
33924 LOCAL_POSITION_NED_COV_DATA::ID => Some(Self::LOCAL_POSITION_NED_COV(
33925 LOCAL_POSITION_NED_COV_DATA::default(),
33926 )),
33927 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
33928 Some(Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(
33929 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::default(),
33930 ))
33931 }
33932 LOGGING_ACK_DATA::ID => Some(Self::LOGGING_ACK(LOGGING_ACK_DATA::default())),
33933 LOGGING_DATA_DATA::ID => Some(Self::LOGGING_DATA(LOGGING_DATA_DATA::default())),
33934 LOGGING_DATA_ACKED_DATA::ID => {
33935 Some(Self::LOGGING_DATA_ACKED(LOGGING_DATA_ACKED_DATA::default()))
33936 }
33937 LOG_DATA_DATA::ID => Some(Self::LOG_DATA(LOG_DATA_DATA::default())),
33938 LOG_ENTRY_DATA::ID => Some(Self::LOG_ENTRY(LOG_ENTRY_DATA::default())),
33939 LOG_ERASE_DATA::ID => Some(Self::LOG_ERASE(LOG_ERASE_DATA::default())),
33940 LOG_REQUEST_DATA_DATA::ID => {
33941 Some(Self::LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA::default()))
33942 }
33943 LOG_REQUEST_END_DATA::ID => {
33944 Some(Self::LOG_REQUEST_END(LOG_REQUEST_END_DATA::default()))
33945 }
33946 LOG_REQUEST_LIST_DATA::ID => {
33947 Some(Self::LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA::default()))
33948 }
33949 MAG_CAL_REPORT_DATA::ID => Some(Self::MAG_CAL_REPORT(MAG_CAL_REPORT_DATA::default())),
33950 MANUAL_CONTROL_DATA::ID => Some(Self::MANUAL_CONTROL(MANUAL_CONTROL_DATA::default())),
33951 MANUAL_SETPOINT_DATA::ID => {
33952 Some(Self::MANUAL_SETPOINT(MANUAL_SETPOINT_DATA::default()))
33953 }
33954 MEMORY_VECT_DATA::ID => Some(Self::MEMORY_VECT(MEMORY_VECT_DATA::default())),
33955 MESSAGE_INTERVAL_DATA::ID => {
33956 Some(Self::MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA::default()))
33957 }
33958 MISSION_ACK_DATA::ID => Some(Self::MISSION_ACK(MISSION_ACK_DATA::default())),
33959 MISSION_CLEAR_ALL_DATA::ID => {
33960 Some(Self::MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA::default()))
33961 }
33962 MISSION_COUNT_DATA::ID => Some(Self::MISSION_COUNT(MISSION_COUNT_DATA::default())),
33963 MISSION_CURRENT_DATA::ID => {
33964 Some(Self::MISSION_CURRENT(MISSION_CURRENT_DATA::default()))
33965 }
33966 MISSION_ITEM_DATA::ID => Some(Self::MISSION_ITEM(MISSION_ITEM_DATA::default())),
33967 MISSION_ITEM_INT_DATA::ID => {
33968 Some(Self::MISSION_ITEM_INT(MISSION_ITEM_INT_DATA::default()))
33969 }
33970 MISSION_ITEM_REACHED_DATA::ID => Some(Self::MISSION_ITEM_REACHED(
33971 MISSION_ITEM_REACHED_DATA::default(),
33972 )),
33973 MISSION_REQUEST_DATA::ID => {
33974 Some(Self::MISSION_REQUEST(MISSION_REQUEST_DATA::default()))
33975 }
33976 MISSION_REQUEST_INT_DATA::ID => Some(Self::MISSION_REQUEST_INT(
33977 MISSION_REQUEST_INT_DATA::default(),
33978 )),
33979 MISSION_REQUEST_LIST_DATA::ID => Some(Self::MISSION_REQUEST_LIST(
33980 MISSION_REQUEST_LIST_DATA::default(),
33981 )),
33982 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_REQUEST_PARTIAL_LIST(
33983 MISSION_REQUEST_PARTIAL_LIST_DATA::default(),
33984 )),
33985 MISSION_SET_CURRENT_DATA::ID => Some(Self::MISSION_SET_CURRENT(
33986 MISSION_SET_CURRENT_DATA::default(),
33987 )),
33988 MISSION_WRITE_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_WRITE_PARTIAL_LIST(
33989 MISSION_WRITE_PARTIAL_LIST_DATA::default(),
33990 )),
33991 MOUNT_ORIENTATION_DATA::ID => {
33992 Some(Self::MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA::default()))
33993 }
33994 NAMED_VALUE_FLOAT_DATA::ID => {
33995 Some(Self::NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA::default()))
33996 }
33997 NAMED_VALUE_INT_DATA::ID => {
33998 Some(Self::NAMED_VALUE_INT(NAMED_VALUE_INT_DATA::default()))
33999 }
34000 NAV_CONTROLLER_OUTPUT_DATA::ID => Some(Self::NAV_CONTROLLER_OUTPUT(
34001 NAV_CONTROLLER_OUTPUT_DATA::default(),
34002 )),
34003 OBSTACLE_DISTANCE_DATA::ID => {
34004 Some(Self::OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA::default()))
34005 }
34006 ODOMETRY_DATA::ID => Some(Self::ODOMETRY(ODOMETRY_DATA::default())),
34007 ONBOARD_COMPUTER_STATUS_DATA::ID => Some(Self::ONBOARD_COMPUTER_STATUS(
34008 ONBOARD_COMPUTER_STATUS_DATA::default(),
34009 )),
34010 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => Some(Self::OPEN_DRONE_ID_ARM_STATUS(
34011 OPEN_DRONE_ID_ARM_STATUS_DATA::default(),
34012 )),
34013 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => Some(Self::OPEN_DRONE_ID_AUTHENTICATION(
34014 OPEN_DRONE_ID_AUTHENTICATION_DATA::default(),
34015 )),
34016 OPEN_DRONE_ID_BASIC_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_BASIC_ID(
34017 OPEN_DRONE_ID_BASIC_ID_DATA::default(),
34018 )),
34019 OPEN_DRONE_ID_LOCATION_DATA::ID => Some(Self::OPEN_DRONE_ID_LOCATION(
34020 OPEN_DRONE_ID_LOCATION_DATA::default(),
34021 )),
34022 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => Some(Self::OPEN_DRONE_ID_MESSAGE_PACK(
34023 OPEN_DRONE_ID_MESSAGE_PACK_DATA::default(),
34024 )),
34025 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_OPERATOR_ID(
34026 OPEN_DRONE_ID_OPERATOR_ID_DATA::default(),
34027 )),
34028 OPEN_DRONE_ID_SELF_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_SELF_ID(
34029 OPEN_DRONE_ID_SELF_ID_DATA::default(),
34030 )),
34031 OPEN_DRONE_ID_SYSTEM_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM(
34032 OPEN_DRONE_ID_SYSTEM_DATA::default(),
34033 )),
34034 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM_UPDATE(
34035 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::default(),
34036 )),
34037 OPTICAL_FLOW_DATA::ID => Some(Self::OPTICAL_FLOW(OPTICAL_FLOW_DATA::default())),
34038 OPTICAL_FLOW_RAD_DATA::ID => {
34039 Some(Self::OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA::default()))
34040 }
34041 ORBIT_EXECUTION_STATUS_DATA::ID => Some(Self::ORBIT_EXECUTION_STATUS(
34042 ORBIT_EXECUTION_STATUS_DATA::default(),
34043 )),
34044 PARAM_EXT_ACK_DATA::ID => Some(Self::PARAM_EXT_ACK(PARAM_EXT_ACK_DATA::default())),
34045 PARAM_EXT_REQUEST_LIST_DATA::ID => Some(Self::PARAM_EXT_REQUEST_LIST(
34046 PARAM_EXT_REQUEST_LIST_DATA::default(),
34047 )),
34048 PARAM_EXT_REQUEST_READ_DATA::ID => Some(Self::PARAM_EXT_REQUEST_READ(
34049 PARAM_EXT_REQUEST_READ_DATA::default(),
34050 )),
34051 PARAM_EXT_SET_DATA::ID => Some(Self::PARAM_EXT_SET(PARAM_EXT_SET_DATA::default())),
34052 PARAM_EXT_VALUE_DATA::ID => {
34053 Some(Self::PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA::default()))
34054 }
34055 PARAM_MAP_RC_DATA::ID => Some(Self::PARAM_MAP_RC(PARAM_MAP_RC_DATA::default())),
34056 PARAM_REQUEST_LIST_DATA::ID => {
34057 Some(Self::PARAM_REQUEST_LIST(PARAM_REQUEST_LIST_DATA::default()))
34058 }
34059 PARAM_REQUEST_READ_DATA::ID => {
34060 Some(Self::PARAM_REQUEST_READ(PARAM_REQUEST_READ_DATA::default()))
34061 }
34062 PARAM_SET_DATA::ID => Some(Self::PARAM_SET(PARAM_SET_DATA::default())),
34063 PARAM_VALUE_DATA::ID => Some(Self::PARAM_VALUE(PARAM_VALUE_DATA::default())),
34064 PING_DATA::ID => Some(Self::PING(PING_DATA::default())),
34065 PLAY_TUNE_DATA::ID => Some(Self::PLAY_TUNE(PLAY_TUNE_DATA::default())),
34066 PLAY_TUNE_V2_DATA::ID => Some(Self::PLAY_TUNE_V2(PLAY_TUNE_V2_DATA::default())),
34067 POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::POSITION_TARGET_GLOBAL_INT(
34068 POSITION_TARGET_GLOBAL_INT_DATA::default(),
34069 )),
34070 POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::POSITION_TARGET_LOCAL_NED(
34071 POSITION_TARGET_LOCAL_NED_DATA::default(),
34072 )),
34073 POWER_STATUS_DATA::ID => Some(Self::POWER_STATUS(POWER_STATUS_DATA::default())),
34074 PROTOCOL_VERSION_DATA::ID => {
34075 Some(Self::PROTOCOL_VERSION(PROTOCOL_VERSION_DATA::default()))
34076 }
34077 RADIO_STATUS_DATA::ID => Some(Self::RADIO_STATUS(RADIO_STATUS_DATA::default())),
34078 RAW_IMU_DATA::ID => Some(Self::RAW_IMU(RAW_IMU_DATA::default())),
34079 RAW_PRESSURE_DATA::ID => Some(Self::RAW_PRESSURE(RAW_PRESSURE_DATA::default())),
34080 RAW_RPM_DATA::ID => Some(Self::RAW_RPM(RAW_RPM_DATA::default())),
34081 RC_CHANNELS_DATA::ID => Some(Self::RC_CHANNELS(RC_CHANNELS_DATA::default())),
34082 RC_CHANNELS_OVERRIDE_DATA::ID => Some(Self::RC_CHANNELS_OVERRIDE(
34083 RC_CHANNELS_OVERRIDE_DATA::default(),
34084 )),
34085 RC_CHANNELS_RAW_DATA::ID => {
34086 Some(Self::RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA::default()))
34087 }
34088 RC_CHANNELS_SCALED_DATA::ID => {
34089 Some(Self::RC_CHANNELS_SCALED(RC_CHANNELS_SCALED_DATA::default()))
34090 }
34091 REQUEST_DATA_STREAM_DATA::ID => Some(Self::REQUEST_DATA_STREAM(
34092 REQUEST_DATA_STREAM_DATA::default(),
34093 )),
34094 REQUEST_EVENT_DATA::ID => Some(Self::REQUEST_EVENT(REQUEST_EVENT_DATA::default())),
34095 RESOURCE_REQUEST_DATA::ID => {
34096 Some(Self::RESOURCE_REQUEST(RESOURCE_REQUEST_DATA::default()))
34097 }
34098 RESPONSE_EVENT_ERROR_DATA::ID => Some(Self::RESPONSE_EVENT_ERROR(
34099 RESPONSE_EVENT_ERROR_DATA::default(),
34100 )),
34101 SAFETY_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_ALLOWED_AREA(
34102 SAFETY_ALLOWED_AREA_DATA::default(),
34103 )),
34104 SAFETY_SET_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_SET_ALLOWED_AREA(
34105 SAFETY_SET_ALLOWED_AREA_DATA::default(),
34106 )),
34107 SCALED_IMU_DATA::ID => Some(Self::SCALED_IMU(SCALED_IMU_DATA::default())),
34108 SCALED_IMU2_DATA::ID => Some(Self::SCALED_IMU2(SCALED_IMU2_DATA::default())),
34109 SCALED_IMU3_DATA::ID => Some(Self::SCALED_IMU3(SCALED_IMU3_DATA::default())),
34110 SCALED_PRESSURE_DATA::ID => {
34111 Some(Self::SCALED_PRESSURE(SCALED_PRESSURE_DATA::default()))
34112 }
34113 SCALED_PRESSURE2_DATA::ID => {
34114 Some(Self::SCALED_PRESSURE2(SCALED_PRESSURE2_DATA::default()))
34115 }
34116 SCALED_PRESSURE3_DATA::ID => {
34117 Some(Self::SCALED_PRESSURE3(SCALED_PRESSURE3_DATA::default()))
34118 }
34119 SERIAL_CONTROL_DATA::ID => Some(Self::SERIAL_CONTROL(SERIAL_CONTROL_DATA::default())),
34120 SERVO_OUTPUT_RAW_DATA::ID => {
34121 Some(Self::SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA::default()))
34122 }
34123 SETUP_SIGNING_DATA::ID => Some(Self::SETUP_SIGNING(SETUP_SIGNING_DATA::default())),
34124 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::SET_ACTUATOR_CONTROL_TARGET(
34125 SET_ACTUATOR_CONTROL_TARGET_DATA::default(),
34126 )),
34127 SET_ATTITUDE_TARGET_DATA::ID => Some(Self::SET_ATTITUDE_TARGET(
34128 SET_ATTITUDE_TARGET_DATA::default(),
34129 )),
34130 SET_GPS_GLOBAL_ORIGIN_DATA::ID => Some(Self::SET_GPS_GLOBAL_ORIGIN(
34131 SET_GPS_GLOBAL_ORIGIN_DATA::default(),
34132 )),
34133 SET_HOME_POSITION_DATA::ID => {
34134 Some(Self::SET_HOME_POSITION(SET_HOME_POSITION_DATA::default()))
34135 }
34136 SET_MODE_DATA::ID => Some(Self::SET_MODE(SET_MODE_DATA::default())),
34137 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::SET_POSITION_TARGET_GLOBAL_INT(
34138 SET_POSITION_TARGET_GLOBAL_INT_DATA::default(),
34139 )),
34140 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::SET_POSITION_TARGET_LOCAL_NED(
34141 SET_POSITION_TARGET_LOCAL_NED_DATA::default(),
34142 )),
34143 SIM_STATE_DATA::ID => Some(Self::SIM_STATE(SIM_STATE_DATA::default())),
34144 SMART_BATTERY_INFO_DATA::ID => {
34145 Some(Self::SMART_BATTERY_INFO(SMART_BATTERY_INFO_DATA::default()))
34146 }
34147 STATUSTEXT_DATA::ID => Some(Self::STATUSTEXT(STATUSTEXT_DATA::default())),
34148 STORAGE_INFORMATION_DATA::ID => Some(Self::STORAGE_INFORMATION(
34149 STORAGE_INFORMATION_DATA::default(),
34150 )),
34151 SUPPORTED_TUNES_DATA::ID => {
34152 Some(Self::SUPPORTED_TUNES(SUPPORTED_TUNES_DATA::default()))
34153 }
34154 SYSTEM_TIME_DATA::ID => Some(Self::SYSTEM_TIME(SYSTEM_TIME_DATA::default())),
34155 SYS_STATUS_DATA::ID => Some(Self::SYS_STATUS(SYS_STATUS_DATA::default())),
34156 TERRAIN_CHECK_DATA::ID => Some(Self::TERRAIN_CHECK(TERRAIN_CHECK_DATA::default())),
34157 TERRAIN_DATA_DATA::ID => Some(Self::TERRAIN_DATA(TERRAIN_DATA_DATA::default())),
34158 TERRAIN_REPORT_DATA::ID => Some(Self::TERRAIN_REPORT(TERRAIN_REPORT_DATA::default())),
34159 TERRAIN_REQUEST_DATA::ID => {
34160 Some(Self::TERRAIN_REQUEST(TERRAIN_REQUEST_DATA::default()))
34161 }
34162 TIMESYNC_DATA::ID => Some(Self::TIMESYNC(TIMESYNC_DATA::default())),
34163 TIME_ESTIMATE_TO_TARGET_DATA::ID => Some(Self::TIME_ESTIMATE_TO_TARGET(
34164 TIME_ESTIMATE_TO_TARGET_DATA::default(),
34165 )),
34166 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
34167 Some(Self::TRAJECTORY_REPRESENTATION_BEZIER(
34168 TRAJECTORY_REPRESENTATION_BEZIER_DATA::default(),
34169 ))
34170 }
34171 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
34172 Some(Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(
34173 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::default(),
34174 ))
34175 }
34176 TUNNEL_DATA::ID => Some(Self::TUNNEL(TUNNEL_DATA::default())),
34177 UAVCAN_NODE_INFO_DATA::ID => {
34178 Some(Self::UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA::default()))
34179 }
34180 UAVCAN_NODE_STATUS_DATA::ID => {
34181 Some(Self::UAVCAN_NODE_STATUS(UAVCAN_NODE_STATUS_DATA::default()))
34182 }
34183 UAVIONIX_ADSB_GET_DATA::ID => {
34184 Some(Self::UAVIONIX_ADSB_GET(UAVIONIX_ADSB_GET_DATA::default()))
34185 }
34186 UAVIONIX_ADSB_OUT_CFG_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_CFG(
34187 UAVIONIX_ADSB_OUT_CFG_DATA::default(),
34188 )),
34189 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_CFG_FLIGHTID(
34190 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::default(),
34191 )),
34192 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::ID => {
34193 Some(Self::UAVIONIX_ADSB_OUT_CFG_REGISTRATION(
34194 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::default(),
34195 ))
34196 }
34197 UAVIONIX_ADSB_OUT_CONTROL_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_CONTROL(
34198 UAVIONIX_ADSB_OUT_CONTROL_DATA::default(),
34199 )),
34200 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_DYNAMIC(
34201 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::default(),
34202 )),
34203 UAVIONIX_ADSB_OUT_STATUS_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_STATUS(
34204 UAVIONIX_ADSB_OUT_STATUS_DATA::default(),
34205 )),
34206 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::ID => {
34207 Some(Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(
34208 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::default(),
34209 ))
34210 }
34211 UTM_GLOBAL_POSITION_DATA::ID => Some(Self::UTM_GLOBAL_POSITION(
34212 UTM_GLOBAL_POSITION_DATA::default(),
34213 )),
34214 V2_EXTENSION_DATA::ID => Some(Self::V2_EXTENSION(V2_EXTENSION_DATA::default())),
34215 VFR_HUD_DATA::ID => Some(Self::VFR_HUD(VFR_HUD_DATA::default())),
34216 VIBRATION_DATA::ID => Some(Self::VIBRATION(VIBRATION_DATA::default())),
34217 VICON_POSITION_ESTIMATE_DATA::ID => Some(Self::VICON_POSITION_ESTIMATE(
34218 VICON_POSITION_ESTIMATE_DATA::default(),
34219 )),
34220 VIDEO_STREAM_INFORMATION_DATA::ID => Some(Self::VIDEO_STREAM_INFORMATION(
34221 VIDEO_STREAM_INFORMATION_DATA::default(),
34222 )),
34223 VIDEO_STREAM_STATUS_DATA::ID => Some(Self::VIDEO_STREAM_STATUS(
34224 VIDEO_STREAM_STATUS_DATA::default(),
34225 )),
34226 VISION_POSITION_ESTIMATE_DATA::ID => Some(Self::VISION_POSITION_ESTIMATE(
34227 VISION_POSITION_ESTIMATE_DATA::default(),
34228 )),
34229 VISION_SPEED_ESTIMATE_DATA::ID => Some(Self::VISION_SPEED_ESTIMATE(
34230 VISION_SPEED_ESTIMATE_DATA::default(),
34231 )),
34232 WHEEL_DISTANCE_DATA::ID => Some(Self::WHEEL_DISTANCE(WHEEL_DISTANCE_DATA::default())),
34233 WIFI_CONFIG_AP_DATA::ID => Some(Self::WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA::default())),
34234 WINCH_STATUS_DATA::ID => Some(Self::WINCH_STATUS(WINCH_STATUS_DATA::default())),
34235 WIND_COV_DATA::ID => Some(Self::WIND_COV(WIND_COV_DATA::default())),
34236 _ => None,
34237 }
34238 }
34239 #[cfg(feature = "arbitrary")]
34240 fn random_message_from_id<R: rand::RngCore>(id: u32, rng: &mut R) -> Option<Self> {
34241 match id {
34242 ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::ACTUATOR_CONTROL_TARGET(
34243 ACTUATOR_CONTROL_TARGET_DATA::random(rng),
34244 )),
34245 ACTUATOR_OUTPUT_STATUS_DATA::ID => Some(Self::ACTUATOR_OUTPUT_STATUS(
34246 ACTUATOR_OUTPUT_STATUS_DATA::random(rng),
34247 )),
34248 ADSB_VEHICLE_DATA::ID => Some(Self::ADSB_VEHICLE(ADSB_VEHICLE_DATA::random(rng))),
34249 AIS_VESSEL_DATA::ID => Some(Self::AIS_VESSEL(AIS_VESSEL_DATA::random(rng))),
34250 ALTITUDE_DATA::ID => Some(Self::ALTITUDE(ALTITUDE_DATA::random(rng))),
34251 ATTITUDE_DATA::ID => Some(Self::ATTITUDE(ATTITUDE_DATA::random(rng))),
34252 ATTITUDE_QUATERNION_DATA::ID => Some(Self::ATTITUDE_QUATERNION(
34253 ATTITUDE_QUATERNION_DATA::random(rng),
34254 )),
34255 ATTITUDE_QUATERNION_COV_DATA::ID => Some(Self::ATTITUDE_QUATERNION_COV(
34256 ATTITUDE_QUATERNION_COV_DATA::random(rng),
34257 )),
34258 ATTITUDE_TARGET_DATA::ID => {
34259 Some(Self::ATTITUDE_TARGET(ATTITUDE_TARGET_DATA::random(rng)))
34260 }
34261 ATT_POS_MOCAP_DATA::ID => Some(Self::ATT_POS_MOCAP(ATT_POS_MOCAP_DATA::random(rng))),
34262 AUTH_KEY_DATA::ID => Some(Self::AUTH_KEY(AUTH_KEY_DATA::random(rng))),
34263 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
34264 Some(Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(
34265 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::random(rng),
34266 ))
34267 }
34268 AUTOPILOT_VERSION_DATA::ID => {
34269 Some(Self::AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA::random(rng)))
34270 }
34271 AVAILABLE_MODES_DATA::ID => {
34272 Some(Self::AVAILABLE_MODES(AVAILABLE_MODES_DATA::random(rng)))
34273 }
34274 AVAILABLE_MODES_MONITOR_DATA::ID => Some(Self::AVAILABLE_MODES_MONITOR(
34275 AVAILABLE_MODES_MONITOR_DATA::random(rng),
34276 )),
34277 BATTERY_INFO_DATA::ID => Some(Self::BATTERY_INFO(BATTERY_INFO_DATA::random(rng))),
34278 BATTERY_STATUS_DATA::ID => Some(Self::BATTERY_STATUS(BATTERY_STATUS_DATA::random(rng))),
34279 BUTTON_CHANGE_DATA::ID => Some(Self::BUTTON_CHANGE(BUTTON_CHANGE_DATA::random(rng))),
34280 CAMERA_CAPTURE_STATUS_DATA::ID => Some(Self::CAMERA_CAPTURE_STATUS(
34281 CAMERA_CAPTURE_STATUS_DATA::random(rng),
34282 )),
34283 CAMERA_FOV_STATUS_DATA::ID => {
34284 Some(Self::CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA::random(rng)))
34285 }
34286 CAMERA_IMAGE_CAPTURED_DATA::ID => Some(Self::CAMERA_IMAGE_CAPTURED(
34287 CAMERA_IMAGE_CAPTURED_DATA::random(rng),
34288 )),
34289 CAMERA_INFORMATION_DATA::ID => Some(Self::CAMERA_INFORMATION(
34290 CAMERA_INFORMATION_DATA::random(rng),
34291 )),
34292 CAMERA_SETTINGS_DATA::ID => {
34293 Some(Self::CAMERA_SETTINGS(CAMERA_SETTINGS_DATA::random(rng)))
34294 }
34295 CAMERA_THERMAL_RANGE_DATA::ID => Some(Self::CAMERA_THERMAL_RANGE(
34296 CAMERA_THERMAL_RANGE_DATA::random(rng),
34297 )),
34298 CAMERA_TRACKING_GEO_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_GEO_STATUS(
34299 CAMERA_TRACKING_GEO_STATUS_DATA::random(rng),
34300 )),
34301 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_IMAGE_STATUS(
34302 CAMERA_TRACKING_IMAGE_STATUS_DATA::random(rng),
34303 )),
34304 CAMERA_TRIGGER_DATA::ID => Some(Self::CAMERA_TRIGGER(CAMERA_TRIGGER_DATA::random(rng))),
34305 CANFD_FRAME_DATA::ID => Some(Self::CANFD_FRAME(CANFD_FRAME_DATA::random(rng))),
34306 CAN_FILTER_MODIFY_DATA::ID => {
34307 Some(Self::CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA::random(rng)))
34308 }
34309 CAN_FRAME_DATA::ID => Some(Self::CAN_FRAME(CAN_FRAME_DATA::random(rng))),
34310 CELLULAR_CONFIG_DATA::ID => {
34311 Some(Self::CELLULAR_CONFIG(CELLULAR_CONFIG_DATA::random(rng)))
34312 }
34313 CELLULAR_STATUS_DATA::ID => {
34314 Some(Self::CELLULAR_STATUS(CELLULAR_STATUS_DATA::random(rng)))
34315 }
34316 CHANGE_OPERATOR_CONTROL_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL(
34317 CHANGE_OPERATOR_CONTROL_DATA::random(rng),
34318 )),
34319 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL_ACK(
34320 CHANGE_OPERATOR_CONTROL_ACK_DATA::random(rng),
34321 )),
34322 COLLISION_DATA::ID => Some(Self::COLLISION(COLLISION_DATA::random(rng))),
34323 COMMAND_ACK_DATA::ID => Some(Self::COMMAND_ACK(COMMAND_ACK_DATA::random(rng))),
34324 COMMAND_CANCEL_DATA::ID => Some(Self::COMMAND_CANCEL(COMMAND_CANCEL_DATA::random(rng))),
34325 COMMAND_INT_DATA::ID => Some(Self::COMMAND_INT(COMMAND_INT_DATA::random(rng))),
34326 COMMAND_LONG_DATA::ID => Some(Self::COMMAND_LONG(COMMAND_LONG_DATA::random(rng))),
34327 COMPONENT_INFORMATION_DATA::ID => Some(Self::COMPONENT_INFORMATION(
34328 COMPONENT_INFORMATION_DATA::random(rng),
34329 )),
34330 COMPONENT_INFORMATION_BASIC_DATA::ID => Some(Self::COMPONENT_INFORMATION_BASIC(
34331 COMPONENT_INFORMATION_BASIC_DATA::random(rng),
34332 )),
34333 COMPONENT_METADATA_DATA::ID => Some(Self::COMPONENT_METADATA(
34334 COMPONENT_METADATA_DATA::random(rng),
34335 )),
34336 CONTROL_SYSTEM_STATE_DATA::ID => Some(Self::CONTROL_SYSTEM_STATE(
34337 CONTROL_SYSTEM_STATE_DATA::random(rng),
34338 )),
34339 CURRENT_EVENT_SEQUENCE_DATA::ID => Some(Self::CURRENT_EVENT_SEQUENCE(
34340 CURRENT_EVENT_SEQUENCE_DATA::random(rng),
34341 )),
34342 CURRENT_MODE_DATA::ID => Some(Self::CURRENT_MODE(CURRENT_MODE_DATA::random(rng))),
34343 DATA_STREAM_DATA::ID => Some(Self::DATA_STREAM(DATA_STREAM_DATA::random(rng))),
34344 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => Some(Self::DATA_TRANSMISSION_HANDSHAKE(
34345 DATA_TRANSMISSION_HANDSHAKE_DATA::random(rng),
34346 )),
34347 DEBUG_DATA::ID => Some(Self::DEBUG(DEBUG_DATA::random(rng))),
34348 DEBUG_FLOAT_ARRAY_DATA::ID => {
34349 Some(Self::DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA::random(rng)))
34350 }
34351 DEBUG_VECT_DATA::ID => Some(Self::DEBUG_VECT(DEBUG_VECT_DATA::random(rng))),
34352 DISTANCE_SENSOR_DATA::ID => {
34353 Some(Self::DISTANCE_SENSOR(DISTANCE_SENSOR_DATA::random(rng)))
34354 }
34355 EFI_STATUS_DATA::ID => Some(Self::EFI_STATUS(EFI_STATUS_DATA::random(rng))),
34356 ENCAPSULATED_DATA_DATA::ID => {
34357 Some(Self::ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA::random(rng)))
34358 }
34359 ESC_INFO_DATA::ID => Some(Self::ESC_INFO(ESC_INFO_DATA::random(rng))),
34360 ESC_STATUS_DATA::ID => Some(Self::ESC_STATUS(ESC_STATUS_DATA::random(rng))),
34361 ESTIMATOR_STATUS_DATA::ID => {
34362 Some(Self::ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA::random(rng)))
34363 }
34364 EVENT_DATA::ID => Some(Self::EVENT(EVENT_DATA::random(rng))),
34365 EXTENDED_SYS_STATE_DATA::ID => Some(Self::EXTENDED_SYS_STATE(
34366 EXTENDED_SYS_STATE_DATA::random(rng),
34367 )),
34368 FENCE_STATUS_DATA::ID => Some(Self::FENCE_STATUS(FENCE_STATUS_DATA::random(rng))),
34369 FILE_TRANSFER_PROTOCOL_DATA::ID => Some(Self::FILE_TRANSFER_PROTOCOL(
34370 FILE_TRANSFER_PROTOCOL_DATA::random(rng),
34371 )),
34372 FLIGHT_INFORMATION_DATA::ID => Some(Self::FLIGHT_INFORMATION(
34373 FLIGHT_INFORMATION_DATA::random(rng),
34374 )),
34375 FOLLOW_TARGET_DATA::ID => Some(Self::FOLLOW_TARGET(FOLLOW_TARGET_DATA::random(rng))),
34376 FUEL_STATUS_DATA::ID => Some(Self::FUEL_STATUS(FUEL_STATUS_DATA::random(rng))),
34377 GENERATOR_STATUS_DATA::ID => {
34378 Some(Self::GENERATOR_STATUS(GENERATOR_STATUS_DATA::random(rng)))
34379 }
34380 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => Some(Self::GIMBAL_DEVICE_ATTITUDE_STATUS(
34381 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::random(rng),
34382 )),
34383 GIMBAL_DEVICE_INFORMATION_DATA::ID => Some(Self::GIMBAL_DEVICE_INFORMATION(
34384 GIMBAL_DEVICE_INFORMATION_DATA::random(rng),
34385 )),
34386 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_DEVICE_SET_ATTITUDE(
34387 GIMBAL_DEVICE_SET_ATTITUDE_DATA::random(rng),
34388 )),
34389 GIMBAL_MANAGER_INFORMATION_DATA::ID => Some(Self::GIMBAL_MANAGER_INFORMATION(
34390 GIMBAL_MANAGER_INFORMATION_DATA::random(rng),
34391 )),
34392 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_ATTITUDE(
34393 GIMBAL_MANAGER_SET_ATTITUDE_DATA::random(rng),
34394 )),
34395 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
34396 Some(Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(
34397 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::random(rng),
34398 ))
34399 }
34400 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_PITCHYAW(
34401 GIMBAL_MANAGER_SET_PITCHYAW_DATA::random(rng),
34402 )),
34403 GIMBAL_MANAGER_STATUS_DATA::ID => Some(Self::GIMBAL_MANAGER_STATUS(
34404 GIMBAL_MANAGER_STATUS_DATA::random(rng),
34405 )),
34406 GLOBAL_POSITION_INT_DATA::ID => Some(Self::GLOBAL_POSITION_INT(
34407 GLOBAL_POSITION_INT_DATA::random(rng),
34408 )),
34409 GLOBAL_POSITION_INT_COV_DATA::ID => Some(Self::GLOBAL_POSITION_INT_COV(
34410 GLOBAL_POSITION_INT_COV_DATA::random(rng),
34411 )),
34412 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
34413 Some(Self::GLOBAL_VISION_POSITION_ESTIMATE(
34414 GLOBAL_VISION_POSITION_ESTIMATE_DATA::random(rng),
34415 ))
34416 }
34417 GPS2_RAW_DATA::ID => Some(Self::GPS2_RAW(GPS2_RAW_DATA::random(rng))),
34418 GPS2_RTK_DATA::ID => Some(Self::GPS2_RTK(GPS2_RTK_DATA::random(rng))),
34419 GPS_GLOBAL_ORIGIN_DATA::ID => {
34420 Some(Self::GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA::random(rng)))
34421 }
34422 GPS_INJECT_DATA_DATA::ID => {
34423 Some(Self::GPS_INJECT_DATA(GPS_INJECT_DATA_DATA::random(rng)))
34424 }
34425 GPS_INPUT_DATA::ID => Some(Self::GPS_INPUT(GPS_INPUT_DATA::random(rng))),
34426 GPS_RAW_INT_DATA::ID => Some(Self::GPS_RAW_INT(GPS_RAW_INT_DATA::random(rng))),
34427 GPS_RTCM_DATA_DATA::ID => Some(Self::GPS_RTCM_DATA(GPS_RTCM_DATA_DATA::random(rng))),
34428 GPS_RTK_DATA::ID => Some(Self::GPS_RTK(GPS_RTK_DATA::random(rng))),
34429 GPS_STATUS_DATA::ID => Some(Self::GPS_STATUS(GPS_STATUS_DATA::random(rng))),
34430 HEARTBEAT_DATA::ID => Some(Self::HEARTBEAT(HEARTBEAT_DATA::random(rng))),
34431 HIGHRES_IMU_DATA::ID => Some(Self::HIGHRES_IMU(HIGHRES_IMU_DATA::random(rng))),
34432 HIGH_LATENCY_DATA::ID => Some(Self::HIGH_LATENCY(HIGH_LATENCY_DATA::random(rng))),
34433 HIGH_LATENCY2_DATA::ID => Some(Self::HIGH_LATENCY2(HIGH_LATENCY2_DATA::random(rng))),
34434 HIL_ACTUATOR_CONTROLS_DATA::ID => Some(Self::HIL_ACTUATOR_CONTROLS(
34435 HIL_ACTUATOR_CONTROLS_DATA::random(rng),
34436 )),
34437 HIL_CONTROLS_DATA::ID => Some(Self::HIL_CONTROLS(HIL_CONTROLS_DATA::random(rng))),
34438 HIL_GPS_DATA::ID => Some(Self::HIL_GPS(HIL_GPS_DATA::random(rng))),
34439 HIL_OPTICAL_FLOW_DATA::ID => {
34440 Some(Self::HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA::random(rng)))
34441 }
34442 HIL_RC_INPUTS_RAW_DATA::ID => {
34443 Some(Self::HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA::random(rng)))
34444 }
34445 HIL_SENSOR_DATA::ID => Some(Self::HIL_SENSOR(HIL_SENSOR_DATA::random(rng))),
34446 HIL_STATE_DATA::ID => Some(Self::HIL_STATE(HIL_STATE_DATA::random(rng))),
34447 HIL_STATE_QUATERNION_DATA::ID => Some(Self::HIL_STATE_QUATERNION(
34448 HIL_STATE_QUATERNION_DATA::random(rng),
34449 )),
34450 HOME_POSITION_DATA::ID => Some(Self::HOME_POSITION(HOME_POSITION_DATA::random(rng))),
34451 HYGROMETER_SENSOR_DATA::ID => {
34452 Some(Self::HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA::random(rng)))
34453 }
34454 ILLUMINATOR_STATUS_DATA::ID => Some(Self::ILLUMINATOR_STATUS(
34455 ILLUMINATOR_STATUS_DATA::random(rng),
34456 )),
34457 ISBD_LINK_STATUS_DATA::ID => {
34458 Some(Self::ISBD_LINK_STATUS(ISBD_LINK_STATUS_DATA::random(rng)))
34459 }
34460 LANDING_TARGET_DATA::ID => Some(Self::LANDING_TARGET(LANDING_TARGET_DATA::random(rng))),
34461 LINK_NODE_STATUS_DATA::ID => {
34462 Some(Self::LINK_NODE_STATUS(LINK_NODE_STATUS_DATA::random(rng)))
34463 }
34464 LOCAL_POSITION_NED_DATA::ID => Some(Self::LOCAL_POSITION_NED(
34465 LOCAL_POSITION_NED_DATA::random(rng),
34466 )),
34467 LOCAL_POSITION_NED_COV_DATA::ID => Some(Self::LOCAL_POSITION_NED_COV(
34468 LOCAL_POSITION_NED_COV_DATA::random(rng),
34469 )),
34470 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
34471 Some(Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(
34472 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::random(rng),
34473 ))
34474 }
34475 LOGGING_ACK_DATA::ID => Some(Self::LOGGING_ACK(LOGGING_ACK_DATA::random(rng))),
34476 LOGGING_DATA_DATA::ID => Some(Self::LOGGING_DATA(LOGGING_DATA_DATA::random(rng))),
34477 LOGGING_DATA_ACKED_DATA::ID => Some(Self::LOGGING_DATA_ACKED(
34478 LOGGING_DATA_ACKED_DATA::random(rng),
34479 )),
34480 LOG_DATA_DATA::ID => Some(Self::LOG_DATA(LOG_DATA_DATA::random(rng))),
34481 LOG_ENTRY_DATA::ID => Some(Self::LOG_ENTRY(LOG_ENTRY_DATA::random(rng))),
34482 LOG_ERASE_DATA::ID => Some(Self::LOG_ERASE(LOG_ERASE_DATA::random(rng))),
34483 LOG_REQUEST_DATA_DATA::ID => {
34484 Some(Self::LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA::random(rng)))
34485 }
34486 LOG_REQUEST_END_DATA::ID => {
34487 Some(Self::LOG_REQUEST_END(LOG_REQUEST_END_DATA::random(rng)))
34488 }
34489 LOG_REQUEST_LIST_DATA::ID => {
34490 Some(Self::LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA::random(rng)))
34491 }
34492 MAG_CAL_REPORT_DATA::ID => Some(Self::MAG_CAL_REPORT(MAG_CAL_REPORT_DATA::random(rng))),
34493 MANUAL_CONTROL_DATA::ID => Some(Self::MANUAL_CONTROL(MANUAL_CONTROL_DATA::random(rng))),
34494 MANUAL_SETPOINT_DATA::ID => {
34495 Some(Self::MANUAL_SETPOINT(MANUAL_SETPOINT_DATA::random(rng)))
34496 }
34497 MEMORY_VECT_DATA::ID => Some(Self::MEMORY_VECT(MEMORY_VECT_DATA::random(rng))),
34498 MESSAGE_INTERVAL_DATA::ID => {
34499 Some(Self::MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA::random(rng)))
34500 }
34501 MISSION_ACK_DATA::ID => Some(Self::MISSION_ACK(MISSION_ACK_DATA::random(rng))),
34502 MISSION_CLEAR_ALL_DATA::ID => {
34503 Some(Self::MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA::random(rng)))
34504 }
34505 MISSION_COUNT_DATA::ID => Some(Self::MISSION_COUNT(MISSION_COUNT_DATA::random(rng))),
34506 MISSION_CURRENT_DATA::ID => {
34507 Some(Self::MISSION_CURRENT(MISSION_CURRENT_DATA::random(rng)))
34508 }
34509 MISSION_ITEM_DATA::ID => Some(Self::MISSION_ITEM(MISSION_ITEM_DATA::random(rng))),
34510 MISSION_ITEM_INT_DATA::ID => {
34511 Some(Self::MISSION_ITEM_INT(MISSION_ITEM_INT_DATA::random(rng)))
34512 }
34513 MISSION_ITEM_REACHED_DATA::ID => Some(Self::MISSION_ITEM_REACHED(
34514 MISSION_ITEM_REACHED_DATA::random(rng),
34515 )),
34516 MISSION_REQUEST_DATA::ID => {
34517 Some(Self::MISSION_REQUEST(MISSION_REQUEST_DATA::random(rng)))
34518 }
34519 MISSION_REQUEST_INT_DATA::ID => Some(Self::MISSION_REQUEST_INT(
34520 MISSION_REQUEST_INT_DATA::random(rng),
34521 )),
34522 MISSION_REQUEST_LIST_DATA::ID => Some(Self::MISSION_REQUEST_LIST(
34523 MISSION_REQUEST_LIST_DATA::random(rng),
34524 )),
34525 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_REQUEST_PARTIAL_LIST(
34526 MISSION_REQUEST_PARTIAL_LIST_DATA::random(rng),
34527 )),
34528 MISSION_SET_CURRENT_DATA::ID => Some(Self::MISSION_SET_CURRENT(
34529 MISSION_SET_CURRENT_DATA::random(rng),
34530 )),
34531 MISSION_WRITE_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_WRITE_PARTIAL_LIST(
34532 MISSION_WRITE_PARTIAL_LIST_DATA::random(rng),
34533 )),
34534 MOUNT_ORIENTATION_DATA::ID => {
34535 Some(Self::MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA::random(rng)))
34536 }
34537 NAMED_VALUE_FLOAT_DATA::ID => {
34538 Some(Self::NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA::random(rng)))
34539 }
34540 NAMED_VALUE_INT_DATA::ID => {
34541 Some(Self::NAMED_VALUE_INT(NAMED_VALUE_INT_DATA::random(rng)))
34542 }
34543 NAV_CONTROLLER_OUTPUT_DATA::ID => Some(Self::NAV_CONTROLLER_OUTPUT(
34544 NAV_CONTROLLER_OUTPUT_DATA::random(rng),
34545 )),
34546 OBSTACLE_DISTANCE_DATA::ID => {
34547 Some(Self::OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA::random(rng)))
34548 }
34549 ODOMETRY_DATA::ID => Some(Self::ODOMETRY(ODOMETRY_DATA::random(rng))),
34550 ONBOARD_COMPUTER_STATUS_DATA::ID => Some(Self::ONBOARD_COMPUTER_STATUS(
34551 ONBOARD_COMPUTER_STATUS_DATA::random(rng),
34552 )),
34553 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => Some(Self::OPEN_DRONE_ID_ARM_STATUS(
34554 OPEN_DRONE_ID_ARM_STATUS_DATA::random(rng),
34555 )),
34556 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => Some(Self::OPEN_DRONE_ID_AUTHENTICATION(
34557 OPEN_DRONE_ID_AUTHENTICATION_DATA::random(rng),
34558 )),
34559 OPEN_DRONE_ID_BASIC_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_BASIC_ID(
34560 OPEN_DRONE_ID_BASIC_ID_DATA::random(rng),
34561 )),
34562 OPEN_DRONE_ID_LOCATION_DATA::ID => Some(Self::OPEN_DRONE_ID_LOCATION(
34563 OPEN_DRONE_ID_LOCATION_DATA::random(rng),
34564 )),
34565 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => Some(Self::OPEN_DRONE_ID_MESSAGE_PACK(
34566 OPEN_DRONE_ID_MESSAGE_PACK_DATA::random(rng),
34567 )),
34568 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_OPERATOR_ID(
34569 OPEN_DRONE_ID_OPERATOR_ID_DATA::random(rng),
34570 )),
34571 OPEN_DRONE_ID_SELF_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_SELF_ID(
34572 OPEN_DRONE_ID_SELF_ID_DATA::random(rng),
34573 )),
34574 OPEN_DRONE_ID_SYSTEM_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM(
34575 OPEN_DRONE_ID_SYSTEM_DATA::random(rng),
34576 )),
34577 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM_UPDATE(
34578 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::random(rng),
34579 )),
34580 OPTICAL_FLOW_DATA::ID => Some(Self::OPTICAL_FLOW(OPTICAL_FLOW_DATA::random(rng))),
34581 OPTICAL_FLOW_RAD_DATA::ID => {
34582 Some(Self::OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA::random(rng)))
34583 }
34584 ORBIT_EXECUTION_STATUS_DATA::ID => Some(Self::ORBIT_EXECUTION_STATUS(
34585 ORBIT_EXECUTION_STATUS_DATA::random(rng),
34586 )),
34587 PARAM_EXT_ACK_DATA::ID => Some(Self::PARAM_EXT_ACK(PARAM_EXT_ACK_DATA::random(rng))),
34588 PARAM_EXT_REQUEST_LIST_DATA::ID => Some(Self::PARAM_EXT_REQUEST_LIST(
34589 PARAM_EXT_REQUEST_LIST_DATA::random(rng),
34590 )),
34591 PARAM_EXT_REQUEST_READ_DATA::ID => Some(Self::PARAM_EXT_REQUEST_READ(
34592 PARAM_EXT_REQUEST_READ_DATA::random(rng),
34593 )),
34594 PARAM_EXT_SET_DATA::ID => Some(Self::PARAM_EXT_SET(PARAM_EXT_SET_DATA::random(rng))),
34595 PARAM_EXT_VALUE_DATA::ID => {
34596 Some(Self::PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA::random(rng)))
34597 }
34598 PARAM_MAP_RC_DATA::ID => Some(Self::PARAM_MAP_RC(PARAM_MAP_RC_DATA::random(rng))),
34599 PARAM_REQUEST_LIST_DATA::ID => Some(Self::PARAM_REQUEST_LIST(
34600 PARAM_REQUEST_LIST_DATA::random(rng),
34601 )),
34602 PARAM_REQUEST_READ_DATA::ID => Some(Self::PARAM_REQUEST_READ(
34603 PARAM_REQUEST_READ_DATA::random(rng),
34604 )),
34605 PARAM_SET_DATA::ID => Some(Self::PARAM_SET(PARAM_SET_DATA::random(rng))),
34606 PARAM_VALUE_DATA::ID => Some(Self::PARAM_VALUE(PARAM_VALUE_DATA::random(rng))),
34607 PING_DATA::ID => Some(Self::PING(PING_DATA::random(rng))),
34608 PLAY_TUNE_DATA::ID => Some(Self::PLAY_TUNE(PLAY_TUNE_DATA::random(rng))),
34609 PLAY_TUNE_V2_DATA::ID => Some(Self::PLAY_TUNE_V2(PLAY_TUNE_V2_DATA::random(rng))),
34610 POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::POSITION_TARGET_GLOBAL_INT(
34611 POSITION_TARGET_GLOBAL_INT_DATA::random(rng),
34612 )),
34613 POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::POSITION_TARGET_LOCAL_NED(
34614 POSITION_TARGET_LOCAL_NED_DATA::random(rng),
34615 )),
34616 POWER_STATUS_DATA::ID => Some(Self::POWER_STATUS(POWER_STATUS_DATA::random(rng))),
34617 PROTOCOL_VERSION_DATA::ID => {
34618 Some(Self::PROTOCOL_VERSION(PROTOCOL_VERSION_DATA::random(rng)))
34619 }
34620 RADIO_STATUS_DATA::ID => Some(Self::RADIO_STATUS(RADIO_STATUS_DATA::random(rng))),
34621 RAW_IMU_DATA::ID => Some(Self::RAW_IMU(RAW_IMU_DATA::random(rng))),
34622 RAW_PRESSURE_DATA::ID => Some(Self::RAW_PRESSURE(RAW_PRESSURE_DATA::random(rng))),
34623 RAW_RPM_DATA::ID => Some(Self::RAW_RPM(RAW_RPM_DATA::random(rng))),
34624 RC_CHANNELS_DATA::ID => Some(Self::RC_CHANNELS(RC_CHANNELS_DATA::random(rng))),
34625 RC_CHANNELS_OVERRIDE_DATA::ID => Some(Self::RC_CHANNELS_OVERRIDE(
34626 RC_CHANNELS_OVERRIDE_DATA::random(rng),
34627 )),
34628 RC_CHANNELS_RAW_DATA::ID => {
34629 Some(Self::RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA::random(rng)))
34630 }
34631 RC_CHANNELS_SCALED_DATA::ID => Some(Self::RC_CHANNELS_SCALED(
34632 RC_CHANNELS_SCALED_DATA::random(rng),
34633 )),
34634 REQUEST_DATA_STREAM_DATA::ID => Some(Self::REQUEST_DATA_STREAM(
34635 REQUEST_DATA_STREAM_DATA::random(rng),
34636 )),
34637 REQUEST_EVENT_DATA::ID => Some(Self::REQUEST_EVENT(REQUEST_EVENT_DATA::random(rng))),
34638 RESOURCE_REQUEST_DATA::ID => {
34639 Some(Self::RESOURCE_REQUEST(RESOURCE_REQUEST_DATA::random(rng)))
34640 }
34641 RESPONSE_EVENT_ERROR_DATA::ID => Some(Self::RESPONSE_EVENT_ERROR(
34642 RESPONSE_EVENT_ERROR_DATA::random(rng),
34643 )),
34644 SAFETY_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_ALLOWED_AREA(
34645 SAFETY_ALLOWED_AREA_DATA::random(rng),
34646 )),
34647 SAFETY_SET_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_SET_ALLOWED_AREA(
34648 SAFETY_SET_ALLOWED_AREA_DATA::random(rng),
34649 )),
34650 SCALED_IMU_DATA::ID => Some(Self::SCALED_IMU(SCALED_IMU_DATA::random(rng))),
34651 SCALED_IMU2_DATA::ID => Some(Self::SCALED_IMU2(SCALED_IMU2_DATA::random(rng))),
34652 SCALED_IMU3_DATA::ID => Some(Self::SCALED_IMU3(SCALED_IMU3_DATA::random(rng))),
34653 SCALED_PRESSURE_DATA::ID => {
34654 Some(Self::SCALED_PRESSURE(SCALED_PRESSURE_DATA::random(rng)))
34655 }
34656 SCALED_PRESSURE2_DATA::ID => {
34657 Some(Self::SCALED_PRESSURE2(SCALED_PRESSURE2_DATA::random(rng)))
34658 }
34659 SCALED_PRESSURE3_DATA::ID => {
34660 Some(Self::SCALED_PRESSURE3(SCALED_PRESSURE3_DATA::random(rng)))
34661 }
34662 SERIAL_CONTROL_DATA::ID => Some(Self::SERIAL_CONTROL(SERIAL_CONTROL_DATA::random(rng))),
34663 SERVO_OUTPUT_RAW_DATA::ID => {
34664 Some(Self::SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA::random(rng)))
34665 }
34666 SETUP_SIGNING_DATA::ID => Some(Self::SETUP_SIGNING(SETUP_SIGNING_DATA::random(rng))),
34667 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::SET_ACTUATOR_CONTROL_TARGET(
34668 SET_ACTUATOR_CONTROL_TARGET_DATA::random(rng),
34669 )),
34670 SET_ATTITUDE_TARGET_DATA::ID => Some(Self::SET_ATTITUDE_TARGET(
34671 SET_ATTITUDE_TARGET_DATA::random(rng),
34672 )),
34673 SET_GPS_GLOBAL_ORIGIN_DATA::ID => Some(Self::SET_GPS_GLOBAL_ORIGIN(
34674 SET_GPS_GLOBAL_ORIGIN_DATA::random(rng),
34675 )),
34676 SET_HOME_POSITION_DATA::ID => {
34677 Some(Self::SET_HOME_POSITION(SET_HOME_POSITION_DATA::random(rng)))
34678 }
34679 SET_MODE_DATA::ID => Some(Self::SET_MODE(SET_MODE_DATA::random(rng))),
34680 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::SET_POSITION_TARGET_GLOBAL_INT(
34681 SET_POSITION_TARGET_GLOBAL_INT_DATA::random(rng),
34682 )),
34683 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::SET_POSITION_TARGET_LOCAL_NED(
34684 SET_POSITION_TARGET_LOCAL_NED_DATA::random(rng),
34685 )),
34686 SIM_STATE_DATA::ID => Some(Self::SIM_STATE(SIM_STATE_DATA::random(rng))),
34687 SMART_BATTERY_INFO_DATA::ID => Some(Self::SMART_BATTERY_INFO(
34688 SMART_BATTERY_INFO_DATA::random(rng),
34689 )),
34690 STATUSTEXT_DATA::ID => Some(Self::STATUSTEXT(STATUSTEXT_DATA::random(rng))),
34691 STORAGE_INFORMATION_DATA::ID => Some(Self::STORAGE_INFORMATION(
34692 STORAGE_INFORMATION_DATA::random(rng),
34693 )),
34694 SUPPORTED_TUNES_DATA::ID => {
34695 Some(Self::SUPPORTED_TUNES(SUPPORTED_TUNES_DATA::random(rng)))
34696 }
34697 SYSTEM_TIME_DATA::ID => Some(Self::SYSTEM_TIME(SYSTEM_TIME_DATA::random(rng))),
34698 SYS_STATUS_DATA::ID => Some(Self::SYS_STATUS(SYS_STATUS_DATA::random(rng))),
34699 TERRAIN_CHECK_DATA::ID => Some(Self::TERRAIN_CHECK(TERRAIN_CHECK_DATA::random(rng))),
34700 TERRAIN_DATA_DATA::ID => Some(Self::TERRAIN_DATA(TERRAIN_DATA_DATA::random(rng))),
34701 TERRAIN_REPORT_DATA::ID => Some(Self::TERRAIN_REPORT(TERRAIN_REPORT_DATA::random(rng))),
34702 TERRAIN_REQUEST_DATA::ID => {
34703 Some(Self::TERRAIN_REQUEST(TERRAIN_REQUEST_DATA::random(rng)))
34704 }
34705 TIMESYNC_DATA::ID => Some(Self::TIMESYNC(TIMESYNC_DATA::random(rng))),
34706 TIME_ESTIMATE_TO_TARGET_DATA::ID => Some(Self::TIME_ESTIMATE_TO_TARGET(
34707 TIME_ESTIMATE_TO_TARGET_DATA::random(rng),
34708 )),
34709 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
34710 Some(Self::TRAJECTORY_REPRESENTATION_BEZIER(
34711 TRAJECTORY_REPRESENTATION_BEZIER_DATA::random(rng),
34712 ))
34713 }
34714 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
34715 Some(Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(
34716 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::random(rng),
34717 ))
34718 }
34719 TUNNEL_DATA::ID => Some(Self::TUNNEL(TUNNEL_DATA::random(rng))),
34720 UAVCAN_NODE_INFO_DATA::ID => {
34721 Some(Self::UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA::random(rng)))
34722 }
34723 UAVCAN_NODE_STATUS_DATA::ID => Some(Self::UAVCAN_NODE_STATUS(
34724 UAVCAN_NODE_STATUS_DATA::random(rng),
34725 )),
34726 UAVIONIX_ADSB_GET_DATA::ID => {
34727 Some(Self::UAVIONIX_ADSB_GET(UAVIONIX_ADSB_GET_DATA::random(rng)))
34728 }
34729 UAVIONIX_ADSB_OUT_CFG_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_CFG(
34730 UAVIONIX_ADSB_OUT_CFG_DATA::random(rng),
34731 )),
34732 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_CFG_FLIGHTID(
34733 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::random(rng),
34734 )),
34735 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::ID => {
34736 Some(Self::UAVIONIX_ADSB_OUT_CFG_REGISTRATION(
34737 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::random(rng),
34738 ))
34739 }
34740 UAVIONIX_ADSB_OUT_CONTROL_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_CONTROL(
34741 UAVIONIX_ADSB_OUT_CONTROL_DATA::random(rng),
34742 )),
34743 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_DYNAMIC(
34744 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::random(rng),
34745 )),
34746 UAVIONIX_ADSB_OUT_STATUS_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_STATUS(
34747 UAVIONIX_ADSB_OUT_STATUS_DATA::random(rng),
34748 )),
34749 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::ID => {
34750 Some(Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(
34751 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::random(rng),
34752 ))
34753 }
34754 UTM_GLOBAL_POSITION_DATA::ID => Some(Self::UTM_GLOBAL_POSITION(
34755 UTM_GLOBAL_POSITION_DATA::random(rng),
34756 )),
34757 V2_EXTENSION_DATA::ID => Some(Self::V2_EXTENSION(V2_EXTENSION_DATA::random(rng))),
34758 VFR_HUD_DATA::ID => Some(Self::VFR_HUD(VFR_HUD_DATA::random(rng))),
34759 VIBRATION_DATA::ID => Some(Self::VIBRATION(VIBRATION_DATA::random(rng))),
34760 VICON_POSITION_ESTIMATE_DATA::ID => Some(Self::VICON_POSITION_ESTIMATE(
34761 VICON_POSITION_ESTIMATE_DATA::random(rng),
34762 )),
34763 VIDEO_STREAM_INFORMATION_DATA::ID => Some(Self::VIDEO_STREAM_INFORMATION(
34764 VIDEO_STREAM_INFORMATION_DATA::random(rng),
34765 )),
34766 VIDEO_STREAM_STATUS_DATA::ID => Some(Self::VIDEO_STREAM_STATUS(
34767 VIDEO_STREAM_STATUS_DATA::random(rng),
34768 )),
34769 VISION_POSITION_ESTIMATE_DATA::ID => Some(Self::VISION_POSITION_ESTIMATE(
34770 VISION_POSITION_ESTIMATE_DATA::random(rng),
34771 )),
34772 VISION_SPEED_ESTIMATE_DATA::ID => Some(Self::VISION_SPEED_ESTIMATE(
34773 VISION_SPEED_ESTIMATE_DATA::random(rng),
34774 )),
34775 WHEEL_DISTANCE_DATA::ID => Some(Self::WHEEL_DISTANCE(WHEEL_DISTANCE_DATA::random(rng))),
34776 WIFI_CONFIG_AP_DATA::ID => Some(Self::WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA::random(rng))),
34777 WINCH_STATUS_DATA::ID => Some(Self::WINCH_STATUS(WINCH_STATUS_DATA::random(rng))),
34778 WIND_COV_DATA::ID => Some(Self::WIND_COV(WIND_COV_DATA::random(rng))),
34779 _ => None,
34780 }
34781 }
34782 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
34783 match self {
34784 Self::ACTUATOR_CONTROL_TARGET(body) => body.ser(version, bytes),
34785 Self::ACTUATOR_OUTPUT_STATUS(body) => body.ser(version, bytes),
34786 Self::ADSB_VEHICLE(body) => body.ser(version, bytes),
34787 Self::AIS_VESSEL(body) => body.ser(version, bytes),
34788 Self::ALTITUDE(body) => body.ser(version, bytes),
34789 Self::ATTITUDE(body) => body.ser(version, bytes),
34790 Self::ATTITUDE_QUATERNION(body) => body.ser(version, bytes),
34791 Self::ATTITUDE_QUATERNION_COV(body) => body.ser(version, bytes),
34792 Self::ATTITUDE_TARGET(body) => body.ser(version, bytes),
34793 Self::ATT_POS_MOCAP(body) => body.ser(version, bytes),
34794 Self::AUTH_KEY(body) => body.ser(version, bytes),
34795 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(body) => body.ser(version, bytes),
34796 Self::AUTOPILOT_VERSION(body) => body.ser(version, bytes),
34797 Self::AVAILABLE_MODES(body) => body.ser(version, bytes),
34798 Self::AVAILABLE_MODES_MONITOR(body) => body.ser(version, bytes),
34799 Self::BATTERY_INFO(body) => body.ser(version, bytes),
34800 Self::BATTERY_STATUS(body) => body.ser(version, bytes),
34801 Self::BUTTON_CHANGE(body) => body.ser(version, bytes),
34802 Self::CAMERA_CAPTURE_STATUS(body) => body.ser(version, bytes),
34803 Self::CAMERA_FOV_STATUS(body) => body.ser(version, bytes),
34804 Self::CAMERA_IMAGE_CAPTURED(body) => body.ser(version, bytes),
34805 Self::CAMERA_INFORMATION(body) => body.ser(version, bytes),
34806 Self::CAMERA_SETTINGS(body) => body.ser(version, bytes),
34807 Self::CAMERA_THERMAL_RANGE(body) => body.ser(version, bytes),
34808 Self::CAMERA_TRACKING_GEO_STATUS(body) => body.ser(version, bytes),
34809 Self::CAMERA_TRACKING_IMAGE_STATUS(body) => body.ser(version, bytes),
34810 Self::CAMERA_TRIGGER(body) => body.ser(version, bytes),
34811 Self::CANFD_FRAME(body) => body.ser(version, bytes),
34812 Self::CAN_FILTER_MODIFY(body) => body.ser(version, bytes),
34813 Self::CAN_FRAME(body) => body.ser(version, bytes),
34814 Self::CELLULAR_CONFIG(body) => body.ser(version, bytes),
34815 Self::CELLULAR_STATUS(body) => body.ser(version, bytes),
34816 Self::CHANGE_OPERATOR_CONTROL(body) => body.ser(version, bytes),
34817 Self::CHANGE_OPERATOR_CONTROL_ACK(body) => body.ser(version, bytes),
34818 Self::COLLISION(body) => body.ser(version, bytes),
34819 Self::COMMAND_ACK(body) => body.ser(version, bytes),
34820 Self::COMMAND_CANCEL(body) => body.ser(version, bytes),
34821 Self::COMMAND_INT(body) => body.ser(version, bytes),
34822 Self::COMMAND_LONG(body) => body.ser(version, bytes),
34823 Self::COMPONENT_INFORMATION(body) => body.ser(version, bytes),
34824 Self::COMPONENT_INFORMATION_BASIC(body) => body.ser(version, bytes),
34825 Self::COMPONENT_METADATA(body) => body.ser(version, bytes),
34826 Self::CONTROL_SYSTEM_STATE(body) => body.ser(version, bytes),
34827 Self::CURRENT_EVENT_SEQUENCE(body) => body.ser(version, bytes),
34828 Self::CURRENT_MODE(body) => body.ser(version, bytes),
34829 Self::DATA_STREAM(body) => body.ser(version, bytes),
34830 Self::DATA_TRANSMISSION_HANDSHAKE(body) => body.ser(version, bytes),
34831 Self::DEBUG(body) => body.ser(version, bytes),
34832 Self::DEBUG_FLOAT_ARRAY(body) => body.ser(version, bytes),
34833 Self::DEBUG_VECT(body) => body.ser(version, bytes),
34834 Self::DISTANCE_SENSOR(body) => body.ser(version, bytes),
34835 Self::EFI_STATUS(body) => body.ser(version, bytes),
34836 Self::ENCAPSULATED_DATA(body) => body.ser(version, bytes),
34837 Self::ESC_INFO(body) => body.ser(version, bytes),
34838 Self::ESC_STATUS(body) => body.ser(version, bytes),
34839 Self::ESTIMATOR_STATUS(body) => body.ser(version, bytes),
34840 Self::EVENT(body) => body.ser(version, bytes),
34841 Self::EXTENDED_SYS_STATE(body) => body.ser(version, bytes),
34842 Self::FENCE_STATUS(body) => body.ser(version, bytes),
34843 Self::FILE_TRANSFER_PROTOCOL(body) => body.ser(version, bytes),
34844 Self::FLIGHT_INFORMATION(body) => body.ser(version, bytes),
34845 Self::FOLLOW_TARGET(body) => body.ser(version, bytes),
34846 Self::FUEL_STATUS(body) => body.ser(version, bytes),
34847 Self::GENERATOR_STATUS(body) => body.ser(version, bytes),
34848 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(body) => body.ser(version, bytes),
34849 Self::GIMBAL_DEVICE_INFORMATION(body) => body.ser(version, bytes),
34850 Self::GIMBAL_DEVICE_SET_ATTITUDE(body) => body.ser(version, bytes),
34851 Self::GIMBAL_MANAGER_INFORMATION(body) => body.ser(version, bytes),
34852 Self::GIMBAL_MANAGER_SET_ATTITUDE(body) => body.ser(version, bytes),
34853 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(body) => body.ser(version, bytes),
34854 Self::GIMBAL_MANAGER_SET_PITCHYAW(body) => body.ser(version, bytes),
34855 Self::GIMBAL_MANAGER_STATUS(body) => body.ser(version, bytes),
34856 Self::GLOBAL_POSITION_INT(body) => body.ser(version, bytes),
34857 Self::GLOBAL_POSITION_INT_COV(body) => body.ser(version, bytes),
34858 Self::GLOBAL_VISION_POSITION_ESTIMATE(body) => body.ser(version, bytes),
34859 Self::GPS2_RAW(body) => body.ser(version, bytes),
34860 Self::GPS2_RTK(body) => body.ser(version, bytes),
34861 Self::GPS_GLOBAL_ORIGIN(body) => body.ser(version, bytes),
34862 Self::GPS_INJECT_DATA(body) => body.ser(version, bytes),
34863 Self::GPS_INPUT(body) => body.ser(version, bytes),
34864 Self::GPS_RAW_INT(body) => body.ser(version, bytes),
34865 Self::GPS_RTCM_DATA(body) => body.ser(version, bytes),
34866 Self::GPS_RTK(body) => body.ser(version, bytes),
34867 Self::GPS_STATUS(body) => body.ser(version, bytes),
34868 Self::HEARTBEAT(body) => body.ser(version, bytes),
34869 Self::HIGHRES_IMU(body) => body.ser(version, bytes),
34870 Self::HIGH_LATENCY(body) => body.ser(version, bytes),
34871 Self::HIGH_LATENCY2(body) => body.ser(version, bytes),
34872 Self::HIL_ACTUATOR_CONTROLS(body) => body.ser(version, bytes),
34873 Self::HIL_CONTROLS(body) => body.ser(version, bytes),
34874 Self::HIL_GPS(body) => body.ser(version, bytes),
34875 Self::HIL_OPTICAL_FLOW(body) => body.ser(version, bytes),
34876 Self::HIL_RC_INPUTS_RAW(body) => body.ser(version, bytes),
34877 Self::HIL_SENSOR(body) => body.ser(version, bytes),
34878 Self::HIL_STATE(body) => body.ser(version, bytes),
34879 Self::HIL_STATE_QUATERNION(body) => body.ser(version, bytes),
34880 Self::HOME_POSITION(body) => body.ser(version, bytes),
34881 Self::HYGROMETER_SENSOR(body) => body.ser(version, bytes),
34882 Self::ILLUMINATOR_STATUS(body) => body.ser(version, bytes),
34883 Self::ISBD_LINK_STATUS(body) => body.ser(version, bytes),
34884 Self::LANDING_TARGET(body) => body.ser(version, bytes),
34885 Self::LINK_NODE_STATUS(body) => body.ser(version, bytes),
34886 Self::LOCAL_POSITION_NED(body) => body.ser(version, bytes),
34887 Self::LOCAL_POSITION_NED_COV(body) => body.ser(version, bytes),
34888 Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(body) => body.ser(version, bytes),
34889 Self::LOGGING_ACK(body) => body.ser(version, bytes),
34890 Self::LOGGING_DATA(body) => body.ser(version, bytes),
34891 Self::LOGGING_DATA_ACKED(body) => body.ser(version, bytes),
34892 Self::LOG_DATA(body) => body.ser(version, bytes),
34893 Self::LOG_ENTRY(body) => body.ser(version, bytes),
34894 Self::LOG_ERASE(body) => body.ser(version, bytes),
34895 Self::LOG_REQUEST_DATA(body) => body.ser(version, bytes),
34896 Self::LOG_REQUEST_END(body) => body.ser(version, bytes),
34897 Self::LOG_REQUEST_LIST(body) => body.ser(version, bytes),
34898 Self::MAG_CAL_REPORT(body) => body.ser(version, bytes),
34899 Self::MANUAL_CONTROL(body) => body.ser(version, bytes),
34900 Self::MANUAL_SETPOINT(body) => body.ser(version, bytes),
34901 Self::MEMORY_VECT(body) => body.ser(version, bytes),
34902 Self::MESSAGE_INTERVAL(body) => body.ser(version, bytes),
34903 Self::MISSION_ACK(body) => body.ser(version, bytes),
34904 Self::MISSION_CLEAR_ALL(body) => body.ser(version, bytes),
34905 Self::MISSION_COUNT(body) => body.ser(version, bytes),
34906 Self::MISSION_CURRENT(body) => body.ser(version, bytes),
34907 Self::MISSION_ITEM(body) => body.ser(version, bytes),
34908 Self::MISSION_ITEM_INT(body) => body.ser(version, bytes),
34909 Self::MISSION_ITEM_REACHED(body) => body.ser(version, bytes),
34910 Self::MISSION_REQUEST(body) => body.ser(version, bytes),
34911 Self::MISSION_REQUEST_INT(body) => body.ser(version, bytes),
34912 Self::MISSION_REQUEST_LIST(body) => body.ser(version, bytes),
34913 Self::MISSION_REQUEST_PARTIAL_LIST(body) => body.ser(version, bytes),
34914 Self::MISSION_SET_CURRENT(body) => body.ser(version, bytes),
34915 Self::MISSION_WRITE_PARTIAL_LIST(body) => body.ser(version, bytes),
34916 Self::MOUNT_ORIENTATION(body) => body.ser(version, bytes),
34917 Self::NAMED_VALUE_FLOAT(body) => body.ser(version, bytes),
34918 Self::NAMED_VALUE_INT(body) => body.ser(version, bytes),
34919 Self::NAV_CONTROLLER_OUTPUT(body) => body.ser(version, bytes),
34920 Self::OBSTACLE_DISTANCE(body) => body.ser(version, bytes),
34921 Self::ODOMETRY(body) => body.ser(version, bytes),
34922 Self::ONBOARD_COMPUTER_STATUS(body) => body.ser(version, bytes),
34923 Self::OPEN_DRONE_ID_ARM_STATUS(body) => body.ser(version, bytes),
34924 Self::OPEN_DRONE_ID_AUTHENTICATION(body) => body.ser(version, bytes),
34925 Self::OPEN_DRONE_ID_BASIC_ID(body) => body.ser(version, bytes),
34926 Self::OPEN_DRONE_ID_LOCATION(body) => body.ser(version, bytes),
34927 Self::OPEN_DRONE_ID_MESSAGE_PACK(body) => body.ser(version, bytes),
34928 Self::OPEN_DRONE_ID_OPERATOR_ID(body) => body.ser(version, bytes),
34929 Self::OPEN_DRONE_ID_SELF_ID(body) => body.ser(version, bytes),
34930 Self::OPEN_DRONE_ID_SYSTEM(body) => body.ser(version, bytes),
34931 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(body) => body.ser(version, bytes),
34932 Self::OPTICAL_FLOW(body) => body.ser(version, bytes),
34933 Self::OPTICAL_FLOW_RAD(body) => body.ser(version, bytes),
34934 Self::ORBIT_EXECUTION_STATUS(body) => body.ser(version, bytes),
34935 Self::PARAM_EXT_ACK(body) => body.ser(version, bytes),
34936 Self::PARAM_EXT_REQUEST_LIST(body) => body.ser(version, bytes),
34937 Self::PARAM_EXT_REQUEST_READ(body) => body.ser(version, bytes),
34938 Self::PARAM_EXT_SET(body) => body.ser(version, bytes),
34939 Self::PARAM_EXT_VALUE(body) => body.ser(version, bytes),
34940 Self::PARAM_MAP_RC(body) => body.ser(version, bytes),
34941 Self::PARAM_REQUEST_LIST(body) => body.ser(version, bytes),
34942 Self::PARAM_REQUEST_READ(body) => body.ser(version, bytes),
34943 Self::PARAM_SET(body) => body.ser(version, bytes),
34944 Self::PARAM_VALUE(body) => body.ser(version, bytes),
34945 Self::PING(body) => body.ser(version, bytes),
34946 Self::PLAY_TUNE(body) => body.ser(version, bytes),
34947 Self::PLAY_TUNE_V2(body) => body.ser(version, bytes),
34948 Self::POSITION_TARGET_GLOBAL_INT(body) => body.ser(version, bytes),
34949 Self::POSITION_TARGET_LOCAL_NED(body) => body.ser(version, bytes),
34950 Self::POWER_STATUS(body) => body.ser(version, bytes),
34951 Self::PROTOCOL_VERSION(body) => body.ser(version, bytes),
34952 Self::RADIO_STATUS(body) => body.ser(version, bytes),
34953 Self::RAW_IMU(body) => body.ser(version, bytes),
34954 Self::RAW_PRESSURE(body) => body.ser(version, bytes),
34955 Self::RAW_RPM(body) => body.ser(version, bytes),
34956 Self::RC_CHANNELS(body) => body.ser(version, bytes),
34957 Self::RC_CHANNELS_OVERRIDE(body) => body.ser(version, bytes),
34958 Self::RC_CHANNELS_RAW(body) => body.ser(version, bytes),
34959 Self::RC_CHANNELS_SCALED(body) => body.ser(version, bytes),
34960 Self::REQUEST_DATA_STREAM(body) => body.ser(version, bytes),
34961 Self::REQUEST_EVENT(body) => body.ser(version, bytes),
34962 Self::RESOURCE_REQUEST(body) => body.ser(version, bytes),
34963 Self::RESPONSE_EVENT_ERROR(body) => body.ser(version, bytes),
34964 Self::SAFETY_ALLOWED_AREA(body) => body.ser(version, bytes),
34965 Self::SAFETY_SET_ALLOWED_AREA(body) => body.ser(version, bytes),
34966 Self::SCALED_IMU(body) => body.ser(version, bytes),
34967 Self::SCALED_IMU2(body) => body.ser(version, bytes),
34968 Self::SCALED_IMU3(body) => body.ser(version, bytes),
34969 Self::SCALED_PRESSURE(body) => body.ser(version, bytes),
34970 Self::SCALED_PRESSURE2(body) => body.ser(version, bytes),
34971 Self::SCALED_PRESSURE3(body) => body.ser(version, bytes),
34972 Self::SERIAL_CONTROL(body) => body.ser(version, bytes),
34973 Self::SERVO_OUTPUT_RAW(body) => body.ser(version, bytes),
34974 Self::SETUP_SIGNING(body) => body.ser(version, bytes),
34975 Self::SET_ACTUATOR_CONTROL_TARGET(body) => body.ser(version, bytes),
34976 Self::SET_ATTITUDE_TARGET(body) => body.ser(version, bytes),
34977 Self::SET_GPS_GLOBAL_ORIGIN(body) => body.ser(version, bytes),
34978 Self::SET_HOME_POSITION(body) => body.ser(version, bytes),
34979 Self::SET_MODE(body) => body.ser(version, bytes),
34980 Self::SET_POSITION_TARGET_GLOBAL_INT(body) => body.ser(version, bytes),
34981 Self::SET_POSITION_TARGET_LOCAL_NED(body) => body.ser(version, bytes),
34982 Self::SIM_STATE(body) => body.ser(version, bytes),
34983 Self::SMART_BATTERY_INFO(body) => body.ser(version, bytes),
34984 Self::STATUSTEXT(body) => body.ser(version, bytes),
34985 Self::STORAGE_INFORMATION(body) => body.ser(version, bytes),
34986 Self::SUPPORTED_TUNES(body) => body.ser(version, bytes),
34987 Self::SYSTEM_TIME(body) => body.ser(version, bytes),
34988 Self::SYS_STATUS(body) => body.ser(version, bytes),
34989 Self::TERRAIN_CHECK(body) => body.ser(version, bytes),
34990 Self::TERRAIN_DATA(body) => body.ser(version, bytes),
34991 Self::TERRAIN_REPORT(body) => body.ser(version, bytes),
34992 Self::TERRAIN_REQUEST(body) => body.ser(version, bytes),
34993 Self::TIMESYNC(body) => body.ser(version, bytes),
34994 Self::TIME_ESTIMATE_TO_TARGET(body) => body.ser(version, bytes),
34995 Self::TRAJECTORY_REPRESENTATION_BEZIER(body) => body.ser(version, bytes),
34996 Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(body) => body.ser(version, bytes),
34997 Self::TUNNEL(body) => body.ser(version, bytes),
34998 Self::UAVCAN_NODE_INFO(body) => body.ser(version, bytes),
34999 Self::UAVCAN_NODE_STATUS(body) => body.ser(version, bytes),
35000 Self::UAVIONIX_ADSB_GET(body) => body.ser(version, bytes),
35001 Self::UAVIONIX_ADSB_OUT_CFG(body) => body.ser(version, bytes),
35002 Self::UAVIONIX_ADSB_OUT_CFG_FLIGHTID(body) => body.ser(version, bytes),
35003 Self::UAVIONIX_ADSB_OUT_CFG_REGISTRATION(body) => body.ser(version, bytes),
35004 Self::UAVIONIX_ADSB_OUT_CONTROL(body) => body.ser(version, bytes),
35005 Self::UAVIONIX_ADSB_OUT_DYNAMIC(body) => body.ser(version, bytes),
35006 Self::UAVIONIX_ADSB_OUT_STATUS(body) => body.ser(version, bytes),
35007 Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(body) => body.ser(version, bytes),
35008 Self::UTM_GLOBAL_POSITION(body) => body.ser(version, bytes),
35009 Self::V2_EXTENSION(body) => body.ser(version, bytes),
35010 Self::VFR_HUD(body) => body.ser(version, bytes),
35011 Self::VIBRATION(body) => body.ser(version, bytes),
35012 Self::VICON_POSITION_ESTIMATE(body) => body.ser(version, bytes),
35013 Self::VIDEO_STREAM_INFORMATION(body) => body.ser(version, bytes),
35014 Self::VIDEO_STREAM_STATUS(body) => body.ser(version, bytes),
35015 Self::VISION_POSITION_ESTIMATE(body) => body.ser(version, bytes),
35016 Self::VISION_SPEED_ESTIMATE(body) => body.ser(version, bytes),
35017 Self::WHEEL_DISTANCE(body) => body.ser(version, bytes),
35018 Self::WIFI_CONFIG_AP(body) => body.ser(version, bytes),
35019 Self::WINCH_STATUS(body) => body.ser(version, bytes),
35020 Self::WIND_COV(body) => body.ser(version, bytes),
35021 }
35022 }
35023 fn extra_crc(id: u32) -> u8 {
35024 match id {
35025 ACTUATOR_CONTROL_TARGET_DATA::ID => ACTUATOR_CONTROL_TARGET_DATA::EXTRA_CRC,
35026 ACTUATOR_OUTPUT_STATUS_DATA::ID => ACTUATOR_OUTPUT_STATUS_DATA::EXTRA_CRC,
35027 ADSB_VEHICLE_DATA::ID => ADSB_VEHICLE_DATA::EXTRA_CRC,
35028 AIS_VESSEL_DATA::ID => AIS_VESSEL_DATA::EXTRA_CRC,
35029 ALTITUDE_DATA::ID => ALTITUDE_DATA::EXTRA_CRC,
35030 ATTITUDE_DATA::ID => ATTITUDE_DATA::EXTRA_CRC,
35031 ATTITUDE_QUATERNION_DATA::ID => ATTITUDE_QUATERNION_DATA::EXTRA_CRC,
35032 ATTITUDE_QUATERNION_COV_DATA::ID => ATTITUDE_QUATERNION_COV_DATA::EXTRA_CRC,
35033 ATTITUDE_TARGET_DATA::ID => ATTITUDE_TARGET_DATA::EXTRA_CRC,
35034 ATT_POS_MOCAP_DATA::ID => ATT_POS_MOCAP_DATA::EXTRA_CRC,
35035 AUTH_KEY_DATA::ID => AUTH_KEY_DATA::EXTRA_CRC,
35036 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
35037 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::EXTRA_CRC
35038 }
35039 AUTOPILOT_VERSION_DATA::ID => AUTOPILOT_VERSION_DATA::EXTRA_CRC,
35040 AVAILABLE_MODES_DATA::ID => AVAILABLE_MODES_DATA::EXTRA_CRC,
35041 AVAILABLE_MODES_MONITOR_DATA::ID => AVAILABLE_MODES_MONITOR_DATA::EXTRA_CRC,
35042 BATTERY_INFO_DATA::ID => BATTERY_INFO_DATA::EXTRA_CRC,
35043 BATTERY_STATUS_DATA::ID => BATTERY_STATUS_DATA::EXTRA_CRC,
35044 BUTTON_CHANGE_DATA::ID => BUTTON_CHANGE_DATA::EXTRA_CRC,
35045 CAMERA_CAPTURE_STATUS_DATA::ID => CAMERA_CAPTURE_STATUS_DATA::EXTRA_CRC,
35046 CAMERA_FOV_STATUS_DATA::ID => CAMERA_FOV_STATUS_DATA::EXTRA_CRC,
35047 CAMERA_IMAGE_CAPTURED_DATA::ID => CAMERA_IMAGE_CAPTURED_DATA::EXTRA_CRC,
35048 CAMERA_INFORMATION_DATA::ID => CAMERA_INFORMATION_DATA::EXTRA_CRC,
35049 CAMERA_SETTINGS_DATA::ID => CAMERA_SETTINGS_DATA::EXTRA_CRC,
35050 CAMERA_THERMAL_RANGE_DATA::ID => CAMERA_THERMAL_RANGE_DATA::EXTRA_CRC,
35051 CAMERA_TRACKING_GEO_STATUS_DATA::ID => CAMERA_TRACKING_GEO_STATUS_DATA::EXTRA_CRC,
35052 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => CAMERA_TRACKING_IMAGE_STATUS_DATA::EXTRA_CRC,
35053 CAMERA_TRIGGER_DATA::ID => CAMERA_TRIGGER_DATA::EXTRA_CRC,
35054 CANFD_FRAME_DATA::ID => CANFD_FRAME_DATA::EXTRA_CRC,
35055 CAN_FILTER_MODIFY_DATA::ID => CAN_FILTER_MODIFY_DATA::EXTRA_CRC,
35056 CAN_FRAME_DATA::ID => CAN_FRAME_DATA::EXTRA_CRC,
35057 CELLULAR_CONFIG_DATA::ID => CELLULAR_CONFIG_DATA::EXTRA_CRC,
35058 CELLULAR_STATUS_DATA::ID => CELLULAR_STATUS_DATA::EXTRA_CRC,
35059 CHANGE_OPERATOR_CONTROL_DATA::ID => CHANGE_OPERATOR_CONTROL_DATA::EXTRA_CRC,
35060 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => CHANGE_OPERATOR_CONTROL_ACK_DATA::EXTRA_CRC,
35061 COLLISION_DATA::ID => COLLISION_DATA::EXTRA_CRC,
35062 COMMAND_ACK_DATA::ID => COMMAND_ACK_DATA::EXTRA_CRC,
35063 COMMAND_CANCEL_DATA::ID => COMMAND_CANCEL_DATA::EXTRA_CRC,
35064 COMMAND_INT_DATA::ID => COMMAND_INT_DATA::EXTRA_CRC,
35065 COMMAND_LONG_DATA::ID => COMMAND_LONG_DATA::EXTRA_CRC,
35066 COMPONENT_INFORMATION_DATA::ID => COMPONENT_INFORMATION_DATA::EXTRA_CRC,
35067 COMPONENT_INFORMATION_BASIC_DATA::ID => COMPONENT_INFORMATION_BASIC_DATA::EXTRA_CRC,
35068 COMPONENT_METADATA_DATA::ID => COMPONENT_METADATA_DATA::EXTRA_CRC,
35069 CONTROL_SYSTEM_STATE_DATA::ID => CONTROL_SYSTEM_STATE_DATA::EXTRA_CRC,
35070 CURRENT_EVENT_SEQUENCE_DATA::ID => CURRENT_EVENT_SEQUENCE_DATA::EXTRA_CRC,
35071 CURRENT_MODE_DATA::ID => CURRENT_MODE_DATA::EXTRA_CRC,
35072 DATA_STREAM_DATA::ID => DATA_STREAM_DATA::EXTRA_CRC,
35073 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => DATA_TRANSMISSION_HANDSHAKE_DATA::EXTRA_CRC,
35074 DEBUG_DATA::ID => DEBUG_DATA::EXTRA_CRC,
35075 DEBUG_FLOAT_ARRAY_DATA::ID => DEBUG_FLOAT_ARRAY_DATA::EXTRA_CRC,
35076 DEBUG_VECT_DATA::ID => DEBUG_VECT_DATA::EXTRA_CRC,
35077 DISTANCE_SENSOR_DATA::ID => DISTANCE_SENSOR_DATA::EXTRA_CRC,
35078 EFI_STATUS_DATA::ID => EFI_STATUS_DATA::EXTRA_CRC,
35079 ENCAPSULATED_DATA_DATA::ID => ENCAPSULATED_DATA_DATA::EXTRA_CRC,
35080 ESC_INFO_DATA::ID => ESC_INFO_DATA::EXTRA_CRC,
35081 ESC_STATUS_DATA::ID => ESC_STATUS_DATA::EXTRA_CRC,
35082 ESTIMATOR_STATUS_DATA::ID => ESTIMATOR_STATUS_DATA::EXTRA_CRC,
35083 EVENT_DATA::ID => EVENT_DATA::EXTRA_CRC,
35084 EXTENDED_SYS_STATE_DATA::ID => EXTENDED_SYS_STATE_DATA::EXTRA_CRC,
35085 FENCE_STATUS_DATA::ID => FENCE_STATUS_DATA::EXTRA_CRC,
35086 FILE_TRANSFER_PROTOCOL_DATA::ID => FILE_TRANSFER_PROTOCOL_DATA::EXTRA_CRC,
35087 FLIGHT_INFORMATION_DATA::ID => FLIGHT_INFORMATION_DATA::EXTRA_CRC,
35088 FOLLOW_TARGET_DATA::ID => FOLLOW_TARGET_DATA::EXTRA_CRC,
35089 FUEL_STATUS_DATA::ID => FUEL_STATUS_DATA::EXTRA_CRC,
35090 GENERATOR_STATUS_DATA::ID => GENERATOR_STATUS_DATA::EXTRA_CRC,
35091 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::EXTRA_CRC,
35092 GIMBAL_DEVICE_INFORMATION_DATA::ID => GIMBAL_DEVICE_INFORMATION_DATA::EXTRA_CRC,
35093 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => GIMBAL_DEVICE_SET_ATTITUDE_DATA::EXTRA_CRC,
35094 GIMBAL_MANAGER_INFORMATION_DATA::ID => GIMBAL_MANAGER_INFORMATION_DATA::EXTRA_CRC,
35095 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => GIMBAL_MANAGER_SET_ATTITUDE_DATA::EXTRA_CRC,
35096 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
35097 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::EXTRA_CRC
35098 }
35099 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => GIMBAL_MANAGER_SET_PITCHYAW_DATA::EXTRA_CRC,
35100 GIMBAL_MANAGER_STATUS_DATA::ID => GIMBAL_MANAGER_STATUS_DATA::EXTRA_CRC,
35101 GLOBAL_POSITION_INT_DATA::ID => GLOBAL_POSITION_INT_DATA::EXTRA_CRC,
35102 GLOBAL_POSITION_INT_COV_DATA::ID => GLOBAL_POSITION_INT_COV_DATA::EXTRA_CRC,
35103 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
35104 GLOBAL_VISION_POSITION_ESTIMATE_DATA::EXTRA_CRC
35105 }
35106 GPS2_RAW_DATA::ID => GPS2_RAW_DATA::EXTRA_CRC,
35107 GPS2_RTK_DATA::ID => GPS2_RTK_DATA::EXTRA_CRC,
35108 GPS_GLOBAL_ORIGIN_DATA::ID => GPS_GLOBAL_ORIGIN_DATA::EXTRA_CRC,
35109 GPS_INJECT_DATA_DATA::ID => GPS_INJECT_DATA_DATA::EXTRA_CRC,
35110 GPS_INPUT_DATA::ID => GPS_INPUT_DATA::EXTRA_CRC,
35111 GPS_RAW_INT_DATA::ID => GPS_RAW_INT_DATA::EXTRA_CRC,
35112 GPS_RTCM_DATA_DATA::ID => GPS_RTCM_DATA_DATA::EXTRA_CRC,
35113 GPS_RTK_DATA::ID => GPS_RTK_DATA::EXTRA_CRC,
35114 GPS_STATUS_DATA::ID => GPS_STATUS_DATA::EXTRA_CRC,
35115 HEARTBEAT_DATA::ID => HEARTBEAT_DATA::EXTRA_CRC,
35116 HIGHRES_IMU_DATA::ID => HIGHRES_IMU_DATA::EXTRA_CRC,
35117 HIGH_LATENCY_DATA::ID => HIGH_LATENCY_DATA::EXTRA_CRC,
35118 HIGH_LATENCY2_DATA::ID => HIGH_LATENCY2_DATA::EXTRA_CRC,
35119 HIL_ACTUATOR_CONTROLS_DATA::ID => HIL_ACTUATOR_CONTROLS_DATA::EXTRA_CRC,
35120 HIL_CONTROLS_DATA::ID => HIL_CONTROLS_DATA::EXTRA_CRC,
35121 HIL_GPS_DATA::ID => HIL_GPS_DATA::EXTRA_CRC,
35122 HIL_OPTICAL_FLOW_DATA::ID => HIL_OPTICAL_FLOW_DATA::EXTRA_CRC,
35123 HIL_RC_INPUTS_RAW_DATA::ID => HIL_RC_INPUTS_RAW_DATA::EXTRA_CRC,
35124 HIL_SENSOR_DATA::ID => HIL_SENSOR_DATA::EXTRA_CRC,
35125 HIL_STATE_DATA::ID => HIL_STATE_DATA::EXTRA_CRC,
35126 HIL_STATE_QUATERNION_DATA::ID => HIL_STATE_QUATERNION_DATA::EXTRA_CRC,
35127 HOME_POSITION_DATA::ID => HOME_POSITION_DATA::EXTRA_CRC,
35128 HYGROMETER_SENSOR_DATA::ID => HYGROMETER_SENSOR_DATA::EXTRA_CRC,
35129 ILLUMINATOR_STATUS_DATA::ID => ILLUMINATOR_STATUS_DATA::EXTRA_CRC,
35130 ISBD_LINK_STATUS_DATA::ID => ISBD_LINK_STATUS_DATA::EXTRA_CRC,
35131 LANDING_TARGET_DATA::ID => LANDING_TARGET_DATA::EXTRA_CRC,
35132 LINK_NODE_STATUS_DATA::ID => LINK_NODE_STATUS_DATA::EXTRA_CRC,
35133 LOCAL_POSITION_NED_DATA::ID => LOCAL_POSITION_NED_DATA::EXTRA_CRC,
35134 LOCAL_POSITION_NED_COV_DATA::ID => LOCAL_POSITION_NED_COV_DATA::EXTRA_CRC,
35135 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
35136 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::EXTRA_CRC
35137 }
35138 LOGGING_ACK_DATA::ID => LOGGING_ACK_DATA::EXTRA_CRC,
35139 LOGGING_DATA_DATA::ID => LOGGING_DATA_DATA::EXTRA_CRC,
35140 LOGGING_DATA_ACKED_DATA::ID => LOGGING_DATA_ACKED_DATA::EXTRA_CRC,
35141 LOG_DATA_DATA::ID => LOG_DATA_DATA::EXTRA_CRC,
35142 LOG_ENTRY_DATA::ID => LOG_ENTRY_DATA::EXTRA_CRC,
35143 LOG_ERASE_DATA::ID => LOG_ERASE_DATA::EXTRA_CRC,
35144 LOG_REQUEST_DATA_DATA::ID => LOG_REQUEST_DATA_DATA::EXTRA_CRC,
35145 LOG_REQUEST_END_DATA::ID => LOG_REQUEST_END_DATA::EXTRA_CRC,
35146 LOG_REQUEST_LIST_DATA::ID => LOG_REQUEST_LIST_DATA::EXTRA_CRC,
35147 MAG_CAL_REPORT_DATA::ID => MAG_CAL_REPORT_DATA::EXTRA_CRC,
35148 MANUAL_CONTROL_DATA::ID => MANUAL_CONTROL_DATA::EXTRA_CRC,
35149 MANUAL_SETPOINT_DATA::ID => MANUAL_SETPOINT_DATA::EXTRA_CRC,
35150 MEMORY_VECT_DATA::ID => MEMORY_VECT_DATA::EXTRA_CRC,
35151 MESSAGE_INTERVAL_DATA::ID => MESSAGE_INTERVAL_DATA::EXTRA_CRC,
35152 MISSION_ACK_DATA::ID => MISSION_ACK_DATA::EXTRA_CRC,
35153 MISSION_CLEAR_ALL_DATA::ID => MISSION_CLEAR_ALL_DATA::EXTRA_CRC,
35154 MISSION_COUNT_DATA::ID => MISSION_COUNT_DATA::EXTRA_CRC,
35155 MISSION_CURRENT_DATA::ID => MISSION_CURRENT_DATA::EXTRA_CRC,
35156 MISSION_ITEM_DATA::ID => MISSION_ITEM_DATA::EXTRA_CRC,
35157 MISSION_ITEM_INT_DATA::ID => MISSION_ITEM_INT_DATA::EXTRA_CRC,
35158 MISSION_ITEM_REACHED_DATA::ID => MISSION_ITEM_REACHED_DATA::EXTRA_CRC,
35159 MISSION_REQUEST_DATA::ID => MISSION_REQUEST_DATA::EXTRA_CRC,
35160 MISSION_REQUEST_INT_DATA::ID => MISSION_REQUEST_INT_DATA::EXTRA_CRC,
35161 MISSION_REQUEST_LIST_DATA::ID => MISSION_REQUEST_LIST_DATA::EXTRA_CRC,
35162 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => MISSION_REQUEST_PARTIAL_LIST_DATA::EXTRA_CRC,
35163 MISSION_SET_CURRENT_DATA::ID => MISSION_SET_CURRENT_DATA::EXTRA_CRC,
35164 MISSION_WRITE_PARTIAL_LIST_DATA::ID => MISSION_WRITE_PARTIAL_LIST_DATA::EXTRA_CRC,
35165 MOUNT_ORIENTATION_DATA::ID => MOUNT_ORIENTATION_DATA::EXTRA_CRC,
35166 NAMED_VALUE_FLOAT_DATA::ID => NAMED_VALUE_FLOAT_DATA::EXTRA_CRC,
35167 NAMED_VALUE_INT_DATA::ID => NAMED_VALUE_INT_DATA::EXTRA_CRC,
35168 NAV_CONTROLLER_OUTPUT_DATA::ID => NAV_CONTROLLER_OUTPUT_DATA::EXTRA_CRC,
35169 OBSTACLE_DISTANCE_DATA::ID => OBSTACLE_DISTANCE_DATA::EXTRA_CRC,
35170 ODOMETRY_DATA::ID => ODOMETRY_DATA::EXTRA_CRC,
35171 ONBOARD_COMPUTER_STATUS_DATA::ID => ONBOARD_COMPUTER_STATUS_DATA::EXTRA_CRC,
35172 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => OPEN_DRONE_ID_ARM_STATUS_DATA::EXTRA_CRC,
35173 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => OPEN_DRONE_ID_AUTHENTICATION_DATA::EXTRA_CRC,
35174 OPEN_DRONE_ID_BASIC_ID_DATA::ID => OPEN_DRONE_ID_BASIC_ID_DATA::EXTRA_CRC,
35175 OPEN_DRONE_ID_LOCATION_DATA::ID => OPEN_DRONE_ID_LOCATION_DATA::EXTRA_CRC,
35176 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => OPEN_DRONE_ID_MESSAGE_PACK_DATA::EXTRA_CRC,
35177 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => OPEN_DRONE_ID_OPERATOR_ID_DATA::EXTRA_CRC,
35178 OPEN_DRONE_ID_SELF_ID_DATA::ID => OPEN_DRONE_ID_SELF_ID_DATA::EXTRA_CRC,
35179 OPEN_DRONE_ID_SYSTEM_DATA::ID => OPEN_DRONE_ID_SYSTEM_DATA::EXTRA_CRC,
35180 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::EXTRA_CRC,
35181 OPTICAL_FLOW_DATA::ID => OPTICAL_FLOW_DATA::EXTRA_CRC,
35182 OPTICAL_FLOW_RAD_DATA::ID => OPTICAL_FLOW_RAD_DATA::EXTRA_CRC,
35183 ORBIT_EXECUTION_STATUS_DATA::ID => ORBIT_EXECUTION_STATUS_DATA::EXTRA_CRC,
35184 PARAM_EXT_ACK_DATA::ID => PARAM_EXT_ACK_DATA::EXTRA_CRC,
35185 PARAM_EXT_REQUEST_LIST_DATA::ID => PARAM_EXT_REQUEST_LIST_DATA::EXTRA_CRC,
35186 PARAM_EXT_REQUEST_READ_DATA::ID => PARAM_EXT_REQUEST_READ_DATA::EXTRA_CRC,
35187 PARAM_EXT_SET_DATA::ID => PARAM_EXT_SET_DATA::EXTRA_CRC,
35188 PARAM_EXT_VALUE_DATA::ID => PARAM_EXT_VALUE_DATA::EXTRA_CRC,
35189 PARAM_MAP_RC_DATA::ID => PARAM_MAP_RC_DATA::EXTRA_CRC,
35190 PARAM_REQUEST_LIST_DATA::ID => PARAM_REQUEST_LIST_DATA::EXTRA_CRC,
35191 PARAM_REQUEST_READ_DATA::ID => PARAM_REQUEST_READ_DATA::EXTRA_CRC,
35192 PARAM_SET_DATA::ID => PARAM_SET_DATA::EXTRA_CRC,
35193 PARAM_VALUE_DATA::ID => PARAM_VALUE_DATA::EXTRA_CRC,
35194 PING_DATA::ID => PING_DATA::EXTRA_CRC,
35195 PLAY_TUNE_DATA::ID => PLAY_TUNE_DATA::EXTRA_CRC,
35196 PLAY_TUNE_V2_DATA::ID => PLAY_TUNE_V2_DATA::EXTRA_CRC,
35197 POSITION_TARGET_GLOBAL_INT_DATA::ID => POSITION_TARGET_GLOBAL_INT_DATA::EXTRA_CRC,
35198 POSITION_TARGET_LOCAL_NED_DATA::ID => POSITION_TARGET_LOCAL_NED_DATA::EXTRA_CRC,
35199 POWER_STATUS_DATA::ID => POWER_STATUS_DATA::EXTRA_CRC,
35200 PROTOCOL_VERSION_DATA::ID => PROTOCOL_VERSION_DATA::EXTRA_CRC,
35201 RADIO_STATUS_DATA::ID => RADIO_STATUS_DATA::EXTRA_CRC,
35202 RAW_IMU_DATA::ID => RAW_IMU_DATA::EXTRA_CRC,
35203 RAW_PRESSURE_DATA::ID => RAW_PRESSURE_DATA::EXTRA_CRC,
35204 RAW_RPM_DATA::ID => RAW_RPM_DATA::EXTRA_CRC,
35205 RC_CHANNELS_DATA::ID => RC_CHANNELS_DATA::EXTRA_CRC,
35206 RC_CHANNELS_OVERRIDE_DATA::ID => RC_CHANNELS_OVERRIDE_DATA::EXTRA_CRC,
35207 RC_CHANNELS_RAW_DATA::ID => RC_CHANNELS_RAW_DATA::EXTRA_CRC,
35208 RC_CHANNELS_SCALED_DATA::ID => RC_CHANNELS_SCALED_DATA::EXTRA_CRC,
35209 REQUEST_DATA_STREAM_DATA::ID => REQUEST_DATA_STREAM_DATA::EXTRA_CRC,
35210 REQUEST_EVENT_DATA::ID => REQUEST_EVENT_DATA::EXTRA_CRC,
35211 RESOURCE_REQUEST_DATA::ID => RESOURCE_REQUEST_DATA::EXTRA_CRC,
35212 RESPONSE_EVENT_ERROR_DATA::ID => RESPONSE_EVENT_ERROR_DATA::EXTRA_CRC,
35213 SAFETY_ALLOWED_AREA_DATA::ID => SAFETY_ALLOWED_AREA_DATA::EXTRA_CRC,
35214 SAFETY_SET_ALLOWED_AREA_DATA::ID => SAFETY_SET_ALLOWED_AREA_DATA::EXTRA_CRC,
35215 SCALED_IMU_DATA::ID => SCALED_IMU_DATA::EXTRA_CRC,
35216 SCALED_IMU2_DATA::ID => SCALED_IMU2_DATA::EXTRA_CRC,
35217 SCALED_IMU3_DATA::ID => SCALED_IMU3_DATA::EXTRA_CRC,
35218 SCALED_PRESSURE_DATA::ID => SCALED_PRESSURE_DATA::EXTRA_CRC,
35219 SCALED_PRESSURE2_DATA::ID => SCALED_PRESSURE2_DATA::EXTRA_CRC,
35220 SCALED_PRESSURE3_DATA::ID => SCALED_PRESSURE3_DATA::EXTRA_CRC,
35221 SERIAL_CONTROL_DATA::ID => SERIAL_CONTROL_DATA::EXTRA_CRC,
35222 SERVO_OUTPUT_RAW_DATA::ID => SERVO_OUTPUT_RAW_DATA::EXTRA_CRC,
35223 SETUP_SIGNING_DATA::ID => SETUP_SIGNING_DATA::EXTRA_CRC,
35224 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => SET_ACTUATOR_CONTROL_TARGET_DATA::EXTRA_CRC,
35225 SET_ATTITUDE_TARGET_DATA::ID => SET_ATTITUDE_TARGET_DATA::EXTRA_CRC,
35226 SET_GPS_GLOBAL_ORIGIN_DATA::ID => SET_GPS_GLOBAL_ORIGIN_DATA::EXTRA_CRC,
35227 SET_HOME_POSITION_DATA::ID => SET_HOME_POSITION_DATA::EXTRA_CRC,
35228 SET_MODE_DATA::ID => SET_MODE_DATA::EXTRA_CRC,
35229 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => {
35230 SET_POSITION_TARGET_GLOBAL_INT_DATA::EXTRA_CRC
35231 }
35232 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => SET_POSITION_TARGET_LOCAL_NED_DATA::EXTRA_CRC,
35233 SIM_STATE_DATA::ID => SIM_STATE_DATA::EXTRA_CRC,
35234 SMART_BATTERY_INFO_DATA::ID => SMART_BATTERY_INFO_DATA::EXTRA_CRC,
35235 STATUSTEXT_DATA::ID => STATUSTEXT_DATA::EXTRA_CRC,
35236 STORAGE_INFORMATION_DATA::ID => STORAGE_INFORMATION_DATA::EXTRA_CRC,
35237 SUPPORTED_TUNES_DATA::ID => SUPPORTED_TUNES_DATA::EXTRA_CRC,
35238 SYSTEM_TIME_DATA::ID => SYSTEM_TIME_DATA::EXTRA_CRC,
35239 SYS_STATUS_DATA::ID => SYS_STATUS_DATA::EXTRA_CRC,
35240 TERRAIN_CHECK_DATA::ID => TERRAIN_CHECK_DATA::EXTRA_CRC,
35241 TERRAIN_DATA_DATA::ID => TERRAIN_DATA_DATA::EXTRA_CRC,
35242 TERRAIN_REPORT_DATA::ID => TERRAIN_REPORT_DATA::EXTRA_CRC,
35243 TERRAIN_REQUEST_DATA::ID => TERRAIN_REQUEST_DATA::EXTRA_CRC,
35244 TIMESYNC_DATA::ID => TIMESYNC_DATA::EXTRA_CRC,
35245 TIME_ESTIMATE_TO_TARGET_DATA::ID => TIME_ESTIMATE_TO_TARGET_DATA::EXTRA_CRC,
35246 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
35247 TRAJECTORY_REPRESENTATION_BEZIER_DATA::EXTRA_CRC
35248 }
35249 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
35250 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::EXTRA_CRC
35251 }
35252 TUNNEL_DATA::ID => TUNNEL_DATA::EXTRA_CRC,
35253 UAVCAN_NODE_INFO_DATA::ID => UAVCAN_NODE_INFO_DATA::EXTRA_CRC,
35254 UAVCAN_NODE_STATUS_DATA::ID => UAVCAN_NODE_STATUS_DATA::EXTRA_CRC,
35255 UAVIONIX_ADSB_GET_DATA::ID => UAVIONIX_ADSB_GET_DATA::EXTRA_CRC,
35256 UAVIONIX_ADSB_OUT_CFG_DATA::ID => UAVIONIX_ADSB_OUT_CFG_DATA::EXTRA_CRC,
35257 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::ID => {
35258 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::EXTRA_CRC
35259 }
35260 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::ID => {
35261 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::EXTRA_CRC
35262 }
35263 UAVIONIX_ADSB_OUT_CONTROL_DATA::ID => UAVIONIX_ADSB_OUT_CONTROL_DATA::EXTRA_CRC,
35264 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::ID => UAVIONIX_ADSB_OUT_DYNAMIC_DATA::EXTRA_CRC,
35265 UAVIONIX_ADSB_OUT_STATUS_DATA::ID => UAVIONIX_ADSB_OUT_STATUS_DATA::EXTRA_CRC,
35266 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::ID => {
35267 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::EXTRA_CRC
35268 }
35269 UTM_GLOBAL_POSITION_DATA::ID => UTM_GLOBAL_POSITION_DATA::EXTRA_CRC,
35270 V2_EXTENSION_DATA::ID => V2_EXTENSION_DATA::EXTRA_CRC,
35271 VFR_HUD_DATA::ID => VFR_HUD_DATA::EXTRA_CRC,
35272 VIBRATION_DATA::ID => VIBRATION_DATA::EXTRA_CRC,
35273 VICON_POSITION_ESTIMATE_DATA::ID => VICON_POSITION_ESTIMATE_DATA::EXTRA_CRC,
35274 VIDEO_STREAM_INFORMATION_DATA::ID => VIDEO_STREAM_INFORMATION_DATA::EXTRA_CRC,
35275 VIDEO_STREAM_STATUS_DATA::ID => VIDEO_STREAM_STATUS_DATA::EXTRA_CRC,
35276 VISION_POSITION_ESTIMATE_DATA::ID => VISION_POSITION_ESTIMATE_DATA::EXTRA_CRC,
35277 VISION_SPEED_ESTIMATE_DATA::ID => VISION_SPEED_ESTIMATE_DATA::EXTRA_CRC,
35278 WHEEL_DISTANCE_DATA::ID => WHEEL_DISTANCE_DATA::EXTRA_CRC,
35279 WIFI_CONFIG_AP_DATA::ID => WIFI_CONFIG_AP_DATA::EXTRA_CRC,
35280 WINCH_STATUS_DATA::ID => WINCH_STATUS_DATA::EXTRA_CRC,
35281 WIND_COV_DATA::ID => WIND_COV_DATA::EXTRA_CRC,
35282 _ => 0,
35283 }
35284 }
35285 fn target_system_id(&self) -> Option<u8> {
35286 match self {
35287 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(inner) => Some(inner.target_system),
35288 Self::CANFD_FRAME(inner) => Some(inner.target_system),
35289 Self::CAN_FILTER_MODIFY(inner) => Some(inner.target_system),
35290 Self::CAN_FRAME(inner) => Some(inner.target_system),
35291 Self::CHANGE_OPERATOR_CONTROL(inner) => Some(inner.target_system),
35292 Self::COMMAND_ACK(inner) => Some(inner.target_system),
35293 Self::COMMAND_CANCEL(inner) => Some(inner.target_system),
35294 Self::COMMAND_INT(inner) => Some(inner.target_system),
35295 Self::COMMAND_LONG(inner) => Some(inner.target_system),
35296 Self::FILE_TRANSFER_PROTOCOL(inner) => Some(inner.target_system),
35297 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(inner) => Some(inner.target_system),
35298 Self::GIMBAL_DEVICE_SET_ATTITUDE(inner) => Some(inner.target_system),
35299 Self::GIMBAL_MANAGER_SET_ATTITUDE(inner) => Some(inner.target_system),
35300 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(inner) => Some(inner.target_system),
35301 Self::GIMBAL_MANAGER_SET_PITCHYAW(inner) => Some(inner.target_system),
35302 Self::GPS_INJECT_DATA(inner) => Some(inner.target_system),
35303 Self::LOGGING_ACK(inner) => Some(inner.target_system),
35304 Self::LOGGING_DATA(inner) => Some(inner.target_system),
35305 Self::LOGGING_DATA_ACKED(inner) => Some(inner.target_system),
35306 Self::LOG_ERASE(inner) => Some(inner.target_system),
35307 Self::LOG_REQUEST_DATA(inner) => Some(inner.target_system),
35308 Self::LOG_REQUEST_END(inner) => Some(inner.target_system),
35309 Self::LOG_REQUEST_LIST(inner) => Some(inner.target_system),
35310 Self::MISSION_ACK(inner) => Some(inner.target_system),
35311 Self::MISSION_CLEAR_ALL(inner) => Some(inner.target_system),
35312 Self::MISSION_COUNT(inner) => Some(inner.target_system),
35313 Self::MISSION_ITEM(inner) => Some(inner.target_system),
35314 Self::MISSION_ITEM_INT(inner) => Some(inner.target_system),
35315 Self::MISSION_REQUEST(inner) => Some(inner.target_system),
35316 Self::MISSION_REQUEST_INT(inner) => Some(inner.target_system),
35317 Self::MISSION_REQUEST_LIST(inner) => Some(inner.target_system),
35318 Self::MISSION_REQUEST_PARTIAL_LIST(inner) => Some(inner.target_system),
35319 Self::MISSION_SET_CURRENT(inner) => Some(inner.target_system),
35320 Self::MISSION_WRITE_PARTIAL_LIST(inner) => Some(inner.target_system),
35321 Self::OPEN_DRONE_ID_AUTHENTICATION(inner) => Some(inner.target_system),
35322 Self::OPEN_DRONE_ID_BASIC_ID(inner) => Some(inner.target_system),
35323 Self::OPEN_DRONE_ID_LOCATION(inner) => Some(inner.target_system),
35324 Self::OPEN_DRONE_ID_MESSAGE_PACK(inner) => Some(inner.target_system),
35325 Self::OPEN_DRONE_ID_OPERATOR_ID(inner) => Some(inner.target_system),
35326 Self::OPEN_DRONE_ID_SELF_ID(inner) => Some(inner.target_system),
35327 Self::OPEN_DRONE_ID_SYSTEM(inner) => Some(inner.target_system),
35328 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(inner) => Some(inner.target_system),
35329 Self::PARAM_EXT_REQUEST_LIST(inner) => Some(inner.target_system),
35330 Self::PARAM_EXT_REQUEST_READ(inner) => Some(inner.target_system),
35331 Self::PARAM_EXT_SET(inner) => Some(inner.target_system),
35332 Self::PARAM_MAP_RC(inner) => Some(inner.target_system),
35333 Self::PARAM_REQUEST_LIST(inner) => Some(inner.target_system),
35334 Self::PARAM_REQUEST_READ(inner) => Some(inner.target_system),
35335 Self::PARAM_SET(inner) => Some(inner.target_system),
35336 Self::PING(inner) => Some(inner.target_system),
35337 Self::PLAY_TUNE(inner) => Some(inner.target_system),
35338 Self::PLAY_TUNE_V2(inner) => Some(inner.target_system),
35339 Self::RC_CHANNELS_OVERRIDE(inner) => Some(inner.target_system),
35340 Self::REQUEST_DATA_STREAM(inner) => Some(inner.target_system),
35341 Self::REQUEST_EVENT(inner) => Some(inner.target_system),
35342 Self::RESPONSE_EVENT_ERROR(inner) => Some(inner.target_system),
35343 Self::SAFETY_SET_ALLOWED_AREA(inner) => Some(inner.target_system),
35344 Self::SERIAL_CONTROL(inner) => Some(inner.target_system),
35345 Self::SETUP_SIGNING(inner) => Some(inner.target_system),
35346 Self::SET_ACTUATOR_CONTROL_TARGET(inner) => Some(inner.target_system),
35347 Self::SET_ATTITUDE_TARGET(inner) => Some(inner.target_system),
35348 Self::SET_GPS_GLOBAL_ORIGIN(inner) => Some(inner.target_system),
35349 Self::SET_HOME_POSITION(inner) => Some(inner.target_system),
35350 Self::SET_MODE(inner) => Some(inner.target_system),
35351 Self::SET_POSITION_TARGET_GLOBAL_INT(inner) => Some(inner.target_system),
35352 Self::SET_POSITION_TARGET_LOCAL_NED(inner) => Some(inner.target_system),
35353 Self::SUPPORTED_TUNES(inner) => Some(inner.target_system),
35354 Self::TIMESYNC(inner) => Some(inner.target_system),
35355 Self::TUNNEL(inner) => Some(inner.target_system),
35356 Self::V2_EXTENSION(inner) => Some(inner.target_system),
35357 _ => None,
35358 }
35359 }
35360 fn target_component_id(&self) -> Option<u8> {
35361 match self {
35362 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(inner) => Some(inner.target_component),
35363 Self::CANFD_FRAME(inner) => Some(inner.target_component),
35364 Self::CAN_FILTER_MODIFY(inner) => Some(inner.target_component),
35365 Self::CAN_FRAME(inner) => Some(inner.target_component),
35366 Self::COMMAND_ACK(inner) => Some(inner.target_component),
35367 Self::COMMAND_CANCEL(inner) => Some(inner.target_component),
35368 Self::COMMAND_INT(inner) => Some(inner.target_component),
35369 Self::COMMAND_LONG(inner) => Some(inner.target_component),
35370 Self::FILE_TRANSFER_PROTOCOL(inner) => Some(inner.target_component),
35371 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(inner) => Some(inner.target_component),
35372 Self::GIMBAL_DEVICE_SET_ATTITUDE(inner) => Some(inner.target_component),
35373 Self::GIMBAL_MANAGER_SET_ATTITUDE(inner) => Some(inner.target_component),
35374 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(inner) => Some(inner.target_component),
35375 Self::GIMBAL_MANAGER_SET_PITCHYAW(inner) => Some(inner.target_component),
35376 Self::GPS_INJECT_DATA(inner) => Some(inner.target_component),
35377 Self::LOGGING_ACK(inner) => Some(inner.target_component),
35378 Self::LOGGING_DATA(inner) => Some(inner.target_component),
35379 Self::LOGGING_DATA_ACKED(inner) => Some(inner.target_component),
35380 Self::LOG_ERASE(inner) => Some(inner.target_component),
35381 Self::LOG_REQUEST_DATA(inner) => Some(inner.target_component),
35382 Self::LOG_REQUEST_END(inner) => Some(inner.target_component),
35383 Self::LOG_REQUEST_LIST(inner) => Some(inner.target_component),
35384 Self::MISSION_ACK(inner) => Some(inner.target_component),
35385 Self::MISSION_CLEAR_ALL(inner) => Some(inner.target_component),
35386 Self::MISSION_COUNT(inner) => Some(inner.target_component),
35387 Self::MISSION_ITEM(inner) => Some(inner.target_component),
35388 Self::MISSION_ITEM_INT(inner) => Some(inner.target_component),
35389 Self::MISSION_REQUEST(inner) => Some(inner.target_component),
35390 Self::MISSION_REQUEST_INT(inner) => Some(inner.target_component),
35391 Self::MISSION_REQUEST_LIST(inner) => Some(inner.target_component),
35392 Self::MISSION_REQUEST_PARTIAL_LIST(inner) => Some(inner.target_component),
35393 Self::MISSION_SET_CURRENT(inner) => Some(inner.target_component),
35394 Self::MISSION_WRITE_PARTIAL_LIST(inner) => Some(inner.target_component),
35395 Self::OPEN_DRONE_ID_AUTHENTICATION(inner) => Some(inner.target_component),
35396 Self::OPEN_DRONE_ID_BASIC_ID(inner) => Some(inner.target_component),
35397 Self::OPEN_DRONE_ID_LOCATION(inner) => Some(inner.target_component),
35398 Self::OPEN_DRONE_ID_MESSAGE_PACK(inner) => Some(inner.target_component),
35399 Self::OPEN_DRONE_ID_OPERATOR_ID(inner) => Some(inner.target_component),
35400 Self::OPEN_DRONE_ID_SELF_ID(inner) => Some(inner.target_component),
35401 Self::OPEN_DRONE_ID_SYSTEM(inner) => Some(inner.target_component),
35402 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(inner) => Some(inner.target_component),
35403 Self::PARAM_EXT_REQUEST_LIST(inner) => Some(inner.target_component),
35404 Self::PARAM_EXT_REQUEST_READ(inner) => Some(inner.target_component),
35405 Self::PARAM_EXT_SET(inner) => Some(inner.target_component),
35406 Self::PARAM_MAP_RC(inner) => Some(inner.target_component),
35407 Self::PARAM_REQUEST_LIST(inner) => Some(inner.target_component),
35408 Self::PARAM_REQUEST_READ(inner) => Some(inner.target_component),
35409 Self::PARAM_SET(inner) => Some(inner.target_component),
35410 Self::PING(inner) => Some(inner.target_component),
35411 Self::PLAY_TUNE(inner) => Some(inner.target_component),
35412 Self::PLAY_TUNE_V2(inner) => Some(inner.target_component),
35413 Self::RC_CHANNELS_OVERRIDE(inner) => Some(inner.target_component),
35414 Self::REQUEST_DATA_STREAM(inner) => Some(inner.target_component),
35415 Self::REQUEST_EVENT(inner) => Some(inner.target_component),
35416 Self::RESPONSE_EVENT_ERROR(inner) => Some(inner.target_component),
35417 Self::SAFETY_SET_ALLOWED_AREA(inner) => Some(inner.target_component),
35418 Self::SERIAL_CONTROL(inner) => Some(inner.target_component),
35419 Self::SETUP_SIGNING(inner) => Some(inner.target_component),
35420 Self::SET_ACTUATOR_CONTROL_TARGET(inner) => Some(inner.target_component),
35421 Self::SET_ATTITUDE_TARGET(inner) => Some(inner.target_component),
35422 Self::SET_POSITION_TARGET_GLOBAL_INT(inner) => Some(inner.target_component),
35423 Self::SET_POSITION_TARGET_LOCAL_NED(inner) => Some(inner.target_component),
35424 Self::SUPPORTED_TUNES(inner) => Some(inner.target_component),
35425 Self::TIMESYNC(inner) => Some(inner.target_component),
35426 Self::TUNNEL(inner) => Some(inner.target_component),
35427 Self::V2_EXTENSION(inner) => Some(inner.target_component),
35428 _ => None,
35429 }
35430 }
35431}